From cdd9a22322a43f65b72a3a69568d5e992fa3e9c0 Mon Sep 17 00:00:00 2001 From: "james.goppert" Date: Thu, 25 Nov 2010 04:04:30 +0000 Subject: [PATCH] Adding mavlink library (master 5e560f7d76e4a4f431b9b296e7b199899b899145) git-svn-id: https://arducopter.googlecode.com/svn/trunk@922 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/mavlink/README | 25 + libraries/mavlink/doc/Doxyfile | 1521 +++++++++++++++++ libraries/mavlink/doc/README | 9 + libraries/mavlink/doc/mavlink.css | 43 + libraries/mavlink/doc/mavlink.php | 63 + .../mavlink/doc/mavlink_to_html_table.xsl | 36 + .../include/ardupilotmega/ardupilotmega.h | 28 + .../mavlink/include/ardupilotmega/mavlink.h | 11 + libraries/mavlink/include/bittest.c | 39 + libraries/mavlink/include/checksum.h | 95 + libraries/mavlink/include/common/common.h | 71 + libraries/mavlink/include/common/mavlink.h | 11 + .../include/common/mavlink_msg_action.h | 87 + .../include/common/mavlink_msg_action_ack.h | 73 + .../include/common/mavlink_msg_attitude.h | 182 ++ .../mavlink_msg_attitude_controller_output.h | 115 ++ .../mavlink/include/common/mavlink_msg_boot.h | 64 + .../include/common/mavlink_msg_debug.h | 78 + .../common/mavlink_msg_global_position.h | 182 ++ .../include/common/mavlink_msg_gps_raw.h | 215 +++ .../include/common/mavlink_msg_gps_status.h | 144 ++ .../include/common/mavlink_msg_heartbeat.h | 73 + .../common/mavlink_msg_local_position.h | 182 ++ .../mavlink_msg_local_position_setpoint.h | 121 ++ .../mavlink_msg_local_position_setpoint_set.h | 149 ++ .../common/mavlink_msg_manual_control.h | 191 +++ .../common/mavlink_msg_param_request_list.h | 73 + .../common/mavlink_msg_param_request_read.h | 107 ++ .../include/common/mavlink_msg_param_set.h | 109 ++ .../include/common/mavlink_msg_param_value.h | 115 ++ .../mavlink/include/common/mavlink_msg_ping.h | 115 ++ .../mavlink_msg_position_controller_output.h | 115 ++ .../common/mavlink_msg_position_target.h | 121 ++ .../include/common/mavlink_msg_raw_imu.h | 221 +++ .../include/common/mavlink_msg_raw_pressure.h | 125 ++ .../common/mavlink_msg_rc_channels_raw.h | 195 +++ .../common/mavlink_msg_rc_channels_scaled.h | 195 +++ .../common/mavlink_msg_request_data_stream.h | 118 ++ ...ink_msg_request_dynamic_gyro_calibration.h | 123 ++ .../mavlink_msg_request_static_calibration.h | 90 + .../include/common/mavlink_msg_set_altitude.h | 78 + .../include/common/mavlink_msg_set_mode.h | 73 + .../include/common/mavlink_msg_set_nav_mode.h | 73 + .../common/mavlink_msg_state_correction.h | 216 +++ .../include/common/mavlink_msg_statustext.h | 76 + .../include/common/mavlink_msg_sys_status.h | 152 ++ .../include/common/mavlink_msg_system_time.h | 68 + .../include/common/mavlink_msg_waypoint.h | 293 ++++ .../include/common/mavlink_msg_waypoint_ack.h | 87 + .../common/mavlink_msg_waypoint_clear_all.h | 73 + .../common/mavlink_msg_waypoint_count.h | 90 + .../common/mavlink_msg_waypoint_current.h | 62 + .../common/mavlink_msg_waypoint_reached.h | 62 + .../common/mavlink_msg_waypoint_request.h | 90 + .../mavlink_msg_waypoint_request_list.h | 73 + .../common/mavlink_msg_waypoint_set_current.h | 90 + ...avlink_msg_waypoint_set_global_reference.h | 225 +++ libraries/mavlink/include/documentation.dox | 41 + libraries/mavlink/include/mavlink_types.h | 197 +++ libraries/mavlink/include/pixhawk/mavlink.h | 11 + .../pixhawk/mavlink_msg_attitude_control.h | 191 +++ .../include/pixhawk/mavlink_msg_aux_status.h | 147 ++ .../pixhawk/mavlink_msg_control_status.h | 143 ++ .../include/pixhawk/mavlink_msg_debug_vect.h | 142 ++ .../pixhawk/mavlink_msg_image_available.h | 326 ++++ .../mavlink_msg_image_trigger_control.h | 59 + .../pixhawk/mavlink_msg_image_triggered.h | 125 ++ .../pixhawk/mavlink_msg_manual_control.h | 191 +++ .../include/pixhawk/mavlink_msg_marker.h | 176 ++ .../pixhawk/mavlink_msg_pattern_detected.h | 109 ++ .../mavlink_msg_position_control_offset_set.h | 149 ++ .../mavlink_msg_position_control_setpoint.h | 138 ++ ...avlink_msg_position_control_setpoint_set.h | 166 ++ .../include/pixhawk/mavlink_msg_raw_aux.h | 166 ++ .../pixhawk/mavlink_msg_request_data_stream.h | 118 ++ ...ink_msg_request_dynamic_gyro_calibration.h | 123 ++ .../mavlink_msg_request_static_calibration.h | 90 + .../pixhawk/mavlink_msg_set_altitude.h | 78 + .../pixhawk/mavlink_msg_set_cam_shutter.h | 140 ++ .../mavlink_msg_vicon_position_estimate.h | 182 ++ .../mavlink_msg_vision_position_estimate.h | 182 ++ .../pixhawk/mavlink_msg_watchdog_command.h | 107 ++ .../pixhawk/mavlink_msg_watchdog_heartbeat.h | 79 + .../mavlink_msg_watchdog_process_info.h | 132 ++ .../mavlink_msg_watchdog_process_status.h | 143 ++ libraries/mavlink/include/pixhawk/pixhawk.h | 48 + libraries/mavlink/include/protocol.h | 856 ++++++++++ libraries/mavlink/include/slugs/mavlink.h | 11 + .../include/slugs/mavlink_msg_air_data.h | 114 ++ .../include/slugs/mavlink_msg_cpu_load.h | 104 ++ .../include/slugs/mavlink_msg_diagnostic.h | 167 ++ .../include/slugs/mavlink_msg_pilot_console.h | 144 ++ .../include/slugs/mavlink_msg_pwm_commands.h | 229 +++ .../include/slugs/mavlink_msg_sensor_bias.h | 173 ++ libraries/mavlink/include/slugs/slugs.h | 29 + libraries/mavlink/include/ualberta/mavlink.h | 11 + .../ualberta/mavlink_msg_nav_filter_bias.h | 182 ++ .../ualberta/mavlink_msg_radio_calibration.h | 147 ++ .../mavlink_msg_request_radio_calibration.h | 59 + .../mavlink_msg_request_rc_channels.h | 59 + libraries/mavlink/include/ualberta/ualberta.h | 27 + .../message_definitions/ardupilotmega.xml | 6 + .../mavlink/message_definitions/common.xml | 411 +++++ .../mavlink_standard_proposal.xml | 275 +++ .../mavlink/message_definitions/pixhawk.xml | 228 +++ .../mavlink/message_definitions/slugs.xml | 67 + .../mavlink/message_definitions/ualberta.xml | 29 + 107 files changed, 14738 insertions(+) create mode 100644 libraries/mavlink/README create mode 100755 libraries/mavlink/doc/Doxyfile create mode 100644 libraries/mavlink/doc/README create mode 100644 libraries/mavlink/doc/mavlink.css create mode 100644 libraries/mavlink/doc/mavlink.php create mode 100644 libraries/mavlink/doc/mavlink_to_html_table.xsl create mode 100644 libraries/mavlink/include/ardupilotmega/ardupilotmega.h create mode 100644 libraries/mavlink/include/ardupilotmega/mavlink.h create mode 100644 libraries/mavlink/include/bittest.c create mode 100644 libraries/mavlink/include/checksum.h create mode 100644 libraries/mavlink/include/common/common.h create mode 100644 libraries/mavlink/include/common/mavlink.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_action.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_action_ack.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_attitude.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_attitude_controller_output.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_boot.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_debug.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_global_position.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_gps_raw.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_gps_status.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_heartbeat.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_local_position.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_local_position_setpoint.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_local_position_setpoint_set.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_manual_control.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_param_request_list.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_param_request_read.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_param_set.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_param_value.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_ping.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_position_controller_output.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_position_target.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_raw_imu.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_raw_pressure.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_rc_channels_raw.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_rc_channels_scaled.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_request_data_stream.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_request_dynamic_gyro_calibration.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_request_static_calibration.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_set_altitude.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_set_mode.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_set_nav_mode.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_state_correction.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_statustext.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_sys_status.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_system_time.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_waypoint.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_waypoint_ack.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_waypoint_clear_all.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_waypoint_count.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_waypoint_current.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_waypoint_reached.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_waypoint_request.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_waypoint_request_list.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_waypoint_set_current.h create mode 100644 libraries/mavlink/include/common/mavlink_msg_waypoint_set_global_reference.h create mode 100644 libraries/mavlink/include/documentation.dox create mode 100644 libraries/mavlink/include/mavlink_types.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_attitude_control.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_aux_status.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_control_status.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_debug_vect.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_image_available.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_image_trigger_control.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_image_triggered.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_manual_control.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_marker.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_pattern_detected.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_position_control_offset_set.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_raw_aux.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_request_data_stream.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_request_dynamic_gyro_calibration.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_request_static_calibration.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_set_altitude.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_set_cam_shutter.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_vision_position_estimate.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_command.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_process_info.h create mode 100644 libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_process_status.h create mode 100644 libraries/mavlink/include/pixhawk/pixhawk.h create mode 100644 libraries/mavlink/include/protocol.h create mode 100644 libraries/mavlink/include/slugs/mavlink.h create mode 100644 libraries/mavlink/include/slugs/mavlink_msg_air_data.h create mode 100644 libraries/mavlink/include/slugs/mavlink_msg_cpu_load.h create mode 100644 libraries/mavlink/include/slugs/mavlink_msg_diagnostic.h create mode 100644 libraries/mavlink/include/slugs/mavlink_msg_pilot_console.h create mode 100644 libraries/mavlink/include/slugs/mavlink_msg_pwm_commands.h create mode 100644 libraries/mavlink/include/slugs/mavlink_msg_sensor_bias.h create mode 100644 libraries/mavlink/include/slugs/slugs.h create mode 100644 libraries/mavlink/include/ualberta/mavlink.h create mode 100644 libraries/mavlink/include/ualberta/mavlink_msg_nav_filter_bias.h create mode 100644 libraries/mavlink/include/ualberta/mavlink_msg_radio_calibration.h create mode 100644 libraries/mavlink/include/ualberta/mavlink_msg_request_radio_calibration.h create mode 100644 libraries/mavlink/include/ualberta/mavlink_msg_request_rc_channels.h create mode 100644 libraries/mavlink/include/ualberta/ualberta.h create mode 100644 libraries/mavlink/message_definitions/ardupilotmega.xml create mode 100644 libraries/mavlink/message_definitions/common.xml create mode 100644 libraries/mavlink/message_definitions/mavlink_standard_proposal.xml create mode 100644 libraries/mavlink/message_definitions/pixhawk.xml create mode 100644 libraries/mavlink/message_definitions/slugs.xml create mode 100644 libraries/mavlink/message_definitions/ualberta.xml diff --git a/libraries/mavlink/README b/libraries/mavlink/README new file mode 100644 index 0000000000..c2ebb413c3 --- /dev/null +++ b/libraries/mavlink/README @@ -0,0 +1,25 @@ +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 serializes C-structs for serial channels and can be used with +any type of radio modem. + +To generate/update packets, select mavlink_standard_message.xml +in the QGroundControl station settings view, select mavlink/include as +the output directory and click on "Save and Generate". +You will find the newly generated/updated message_xx.h files in +the mavlink/include/generated folder. + +To use MAVLink, #include the file, not 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/ + +For more information, please visit: + +http://pixhawk.ethz.ch/wiki/software/mavlink/ + +(c) 2009-2011 Lorenz Meier / PIXHAWK Team + diff --git a/libraries/mavlink/doc/Doxyfile b/libraries/mavlink/doc/Doxyfile new file mode 100755 index 0000000000..4ab7c0e06f --- /dev/null +++ b/libraries/mavlink/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/libraries/mavlink/doc/README b/libraries/mavlink/doc/README new file mode 100644 index 0000000000..587460140e --- /dev/null +++ b/libraries/mavlink/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://pixhawk.ethz.ch/software/mavlink + +(c) 2009-2010 Lorenz Meier / PIXHAWK Team diff --git a/libraries/mavlink/doc/mavlink.css b/libraries/mavlink/doc/mavlink.css new file mode 100644 index 0000000000..a153bb8aa7 --- /dev/null +++ b/libraries/mavlink/doc/mavlink.css @@ -0,0 +1,43 @@ +table.sortable { + spacing: 5px; + border: 1px solid #656575; + width: 90%; +} + +table.sortable th { + margin: 5px; +} + +table.sortable thead { + background-color:#eee; + color:#666666; + font-weight: bold; + cursor: default; +} + +table.sortable td { + margin: 5px; +} + +table.sortable td.mavlink_name { + color:#226633; + 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/libraries/mavlink/doc/mavlink.php b/libraries/mavlink/doc/mavlink.php new file mode 100644 index 0000000000..871a1306d5 --- /dev/null +++ b/libraries/mavlink/doc/mavlink.php @@ -0,0 +1,63 @@ + + +// Requires the installation of php5-xsl +// e.g. on Debian/Ubuntu: sudo apt-get install php5-xsl + +// Load the file from the repository / server. +// Update this URL if the file location changes + +$xml_file_name = "http://github.com/pixhawk/mavlink/raw/master/mavlink_standard_message.xml"; + +// Load the XSL transformation file from the repository / server. +// This file can be updated by any client to adjust the table + +$xsl_file_name= "http://github.com/pixhawk/mavlink/raw/master/doc/mavlink_to_html_table.xsl"; + + + +// Load data XML file +$xml = file_get_contents($xml_file_name); +$xml_doc = new DomDocument; +$xml_doc->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); + +// process the files and write the output to $out_file +if ($html = $xsltproc->transformToXML($xml_doc)) +{ + echo $html; +} +else +{ + trigger_error('XSL transformation failed.',E_USER_ERROR); +} + + + + +

Messages XML Definition

+ +Messages are defined by the mavlink_standard_message.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. + + +//require_once("inc/geshi.php"); +//$xml_file_name = "http://github.com/pixhawk/mavlink/raw/master/mavlink_standard_message.xml"; +// +//// Load data XML file +//$xml = file_get_contents($xml_file_name); +// +//// Show the current code +//$geshi_xml = new GeSHi($xml, 'xml'); +//$display_xml = $geshi_xml->parse_code(); +// +//echo $display_xml; + + \ No newline at end of file diff --git a/libraries/mavlink/doc/mavlink_to_html_table.xsl b/libraries/mavlink/doc/mavlink_to_html_table.xsl new file mode 100644 index 0000000000..bea6064e8b --- /dev/null +++ b/libraries/mavlink/doc/mavlink_to_html_table.xsl @@ -0,0 +1,36 @@ + + + + + +

MAVLink Messages

+ +
+ + + +

+ + + + + + + + + + + + +
Field NameTypeDescription
+
+ + + + + + + + + +
diff --git a/libraries/mavlink/include/ardupilotmega/ardupilotmega.h b/libraries/mavlink/include/ardupilotmega/ardupilotmega.h new file mode 100644 index 0000000000..67929cb910 --- /dev/null +++ b/libraries/mavlink/include/ardupilotmega/ardupilotmega.h @@ -0,0 +1,28 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Sunday, November 14 2010, 16:32 UTC + */ +#ifndef ARDUPILOTMEGA_H +#define ARDUPILOTMEGA_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_ARDUPILOTMEGA + + +#include "../common/common.h" +// ENUM DEFINITIONS + + +// MESSAGE DEFINITIONS + +#ifdef __cplusplus +} +#endif +#endif diff --git a/libraries/mavlink/include/ardupilotmega/mavlink.h b/libraries/mavlink/include/ardupilotmega/mavlink.h new file mode 100644 index 0000000000..1dd7087f56 --- /dev/null +++ b/libraries/mavlink/include/ardupilotmega/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Sunday, November 14 2010, 16:32 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "ardupilotmega.h" + +#endif diff --git a/libraries/mavlink/include/bittest.c b/libraries/mavlink/include/bittest.c new file mode 100644 index 0000000000..c966b72afb --- /dev/null +++ b/libraries/mavlink/include/bittest.c @@ -0,0 +1,39 @@ +#include +#include + +int main(int argc, char* argv[]) +{ + + uint8_t bitfield = 254; // 11111110 + + uint8_t mask = 128; // 10000000 + + uint8_t result = (bitfield & mask); + + printf("0x%02x\n", bitfield); + + // Transform into network order + + generic_32bit bin; + bin.i = 1; + printf("First byte in (little endian) 0x%02x\n", bin.b[0]); + generic_32bit bout; + bout.b[0] = bin.b[3]; + bout.b[1] = bin.b[2]; + bout.b[2] = bin.b[1]; + bout.b[3] = bin.b[0]; + printf("Last byte out (big endian) 0x%02x\n", bout.b[3]); + + uint8_t n = 5; + printf("Mask is 0x%02x\n", ((uint32_t)(1 << n)) - 1); // = 2^n - 1 + + int32_t encoded = 2; + uint8_t bits = 2; + + uint8_t packet[MAVLINK_MAX_PACKET_LEN]; + uint8_t packet_index = 0; + uint8_t bit_index = 0; + + put_bitfield_n_by_index(encoded, bits, packet_index, bit_index, &bit_index, packet); + +} diff --git a/libraries/mavlink/include/checksum.h b/libraries/mavlink/include/checksum.h new file mode 100644 index 0000000000..c16a06e1b9 --- /dev/null +++ b/libraries/mavlink/include/checksum.h @@ -0,0 +1,95 @@ +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef _CHECKSUM_H_ +#define _CHECKSUM_H_ + +#include "inttypes.h" + + +/** + * + * 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(uint8_t* pBuffer, int length) +{ + + // For a "message" of length bytes contained in the unsigned char array + // pointed to by pBuffer, calculate the CRC + // crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed + + uint16_t crcTmp; + //uint16_t tmp; + uint8_t* pTmp; + int i; + + pTmp=pBuffer; + + + /* init crcTmp */ + crc_init(&crcTmp); + + for (i = 0; i < length; i++){ + crc_accumulate(*pTmp++, &crcTmp); + } + + /* This is currently not needed, as only the checksum over payload should be computed + tmp = crcTmp; + crcAccumulate((unsigned char)(~crcTmp & 0xff),&tmp); + crcAccumulate((unsigned char)((~crcTmp>>8)&0xff),&tmp); + *checkConst = tmp; + */ + return(crcTmp); +} + + + + +#endif /* _CHECKSUM_H_ */ + +#ifdef __cplusplus +} +#endif diff --git a/libraries/mavlink/include/common/common.h b/libraries/mavlink/include/common/common.h new file mode 100644 index 0000000000..1db89612bd --- /dev/null +++ b/libraries/mavlink/include/common/common.h @@ -0,0 +1,71 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Wednesday, November 17 2010, 17:58 UTC + */ +#ifndef COMMON_H +#define COMMON_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_COMMON + +// ENUM DEFINITIONS + + +// MESSAGE DEFINITIONS + +#include "./mavlink_msg_heartbeat.h" +#include "./mavlink_msg_boot.h" +#include "./mavlink_msg_system_time.h" +#include "./mavlink_msg_ping.h" +#include "./mavlink_msg_action.h" +#include "./mavlink_msg_action_ack.h" +#include "./mavlink_msg_set_mode.h" +#include "./mavlink_msg_set_nav_mode.h" +#include "./mavlink_msg_param_request_read.h" +#include "./mavlink_msg_param_request_list.h" +#include "./mavlink_msg_param_value.h" +#include "./mavlink_msg_param_set.h" +#include "./mavlink_msg_raw_imu.h" +#include "./mavlink_msg_raw_pressure.h" +#include "./mavlink_msg_attitude.h" +#include "./mavlink_msg_local_position.h" +#include "./mavlink_msg_gps_raw.h" +#include "./mavlink_msg_gps_status.h" +#include "./mavlink_msg_global_position.h" +#include "./mavlink_msg_sys_status.h" +#include "./mavlink_msg_rc_channels_raw.h" +#include "./mavlink_msg_rc_channels_scaled.h" +#include "./mavlink_msg_waypoint.h" +#include "./mavlink_msg_waypoint_request.h" +#include "./mavlink_msg_waypoint_set_current.h" +#include "./mavlink_msg_waypoint_current.h" +#include "./mavlink_msg_waypoint_request_list.h" +#include "./mavlink_msg_waypoint_count.h" +#include "./mavlink_msg_waypoint_clear_all.h" +#include "./mavlink_msg_waypoint_reached.h" +#include "./mavlink_msg_waypoint_ack.h" +#include "./mavlink_msg_waypoint_set_global_reference.h" +#include "./mavlink_msg_local_position_setpoint_set.h" +#include "./mavlink_msg_local_position_setpoint.h" +#include "./mavlink_msg_attitude_controller_output.h" +#include "./mavlink_msg_position_controller_output.h" +#include "./mavlink_msg_position_target.h" +#include "./mavlink_msg_state_correction.h" +#include "./mavlink_msg_set_altitude.h" +#include "./mavlink_msg_request_data_stream.h" +#include "./mavlink_msg_request_dynamic_gyro_calibration.h" +#include "./mavlink_msg_request_static_calibration.h" +#include "./mavlink_msg_manual_control.h" +#include "./mavlink_msg_statustext.h" +#include "./mavlink_msg_debug.h" +#ifdef __cplusplus +} +#endif +#endif diff --git a/libraries/mavlink/include/common/mavlink.h b/libraries/mavlink/include/common/mavlink.h new file mode 100644 index 0000000000..6e134f54e3 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Wednesday, November 17 2010, 17:58 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "common.h" + +#endif diff --git a/libraries/mavlink/include/common/mavlink_msg_action.h b/libraries/mavlink/include/common/mavlink_msg_action.h new file mode 100644 index 0000000000..668c3a7550 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_action.h @@ -0,0 +1,87 @@ +// MESSAGE ACTION PACKING + +#define MAVLINK_MSG_ID_ACTION 10 + +typedef struct __mavlink_action_t +{ + uint8_t target; ///< The system executing the action + uint8_t target_component; ///< The component executing the action + uint8_t action; ///< The action id + +} mavlink_action_t; + + + +/** + * @brief Send a action message + * + * @param target The system executing the action + * @param target_component The component executing the action + * @param action The action id + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_action_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t target_component, uint8_t action) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ACTION; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system executing the action + i += put_uint8_t_by_index(target_component, i, msg->payload); //The component executing the action + i += put_uint8_t_by_index(action, i, msg->payload); //The action id + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_t* action) +{ + return mavlink_msg_action_pack(system_id, component_id, msg, action->target, action->target_component, action->action); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_action_send(mavlink_channel_t chan, uint8_t target, uint8_t target_component, uint8_t action) +{ + mavlink_message_t msg; + mavlink_msg_action_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, target_component, action); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ACTION UNPACKING + +/** + * @brief Get field target from action message + * + * @return The system executing the action + */ +static inline uint8_t mavlink_msg_action_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from action message + * + * @return The component executing the action + */ +static inline uint8_t mavlink_msg_action_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field action from action message + * + * @return The action id + */ +static inline uint8_t mavlink_msg_action_get_action(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_action_decode(const mavlink_message_t* msg, mavlink_action_t* action) +{ + action->target = mavlink_msg_action_get_target(msg); + action->target_component = mavlink_msg_action_get_target_component(msg); + action->action = mavlink_msg_action_get_action(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_action_ack.h b/libraries/mavlink/include/common/mavlink_msg_action_ack.h new file mode 100644 index 0000000000..9038a85283 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_action_ack.h @@ -0,0 +1,73 @@ +// MESSAGE ACTION_ACK PACKING + +#define MAVLINK_MSG_ID_ACTION_ACK 62 + +typedef struct __mavlink_action_ack_t +{ + uint8_t action; ///< The action id + uint8_t result; ///< 0: Action DENIED, 1: Action executed + +} mavlink_action_ack_t; + + + +/** + * @brief Send a action_ack message + * + * @param action The action id + * @param result 0: Action DENIED, 1: Action executed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_action_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t action, uint8_t result) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ACTION_ACK; + + i += put_uint8_t_by_index(action, i, msg->payload); //The action id + i += put_uint8_t_by_index(result, i, msg->payload); //0: Action DENIED, 1: Action executed + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_action_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_ack_t* action_ack) +{ + return mavlink_msg_action_ack_pack(system_id, component_id, msg, action_ack->action, action_ack->result); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_action_ack_send(mavlink_channel_t chan, uint8_t action, uint8_t result) +{ + mavlink_message_t msg; + mavlink_msg_action_ack_pack(mavlink_system.sysid, mavlink_system.compid, &msg, action, result); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ACTION_ACK UNPACKING + +/** + * @brief Get field action from action_ack message + * + * @return The action id + */ +static inline uint8_t mavlink_msg_action_ack_get_action(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field result from action_ack message + * + * @return 0: Action DENIED, 1: Action executed + */ +static inline uint8_t mavlink_msg_action_ack_get_result(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_action_ack_decode(const mavlink_message_t* msg, mavlink_action_ack_t* action_ack) +{ + action_ack->action = mavlink_msg_action_ack_get_action(msg); + action_ack->result = mavlink_msg_action_ack_get_result(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_attitude.h b/libraries/mavlink/include/common/mavlink_msg_attitude.h new file mode 100644 index 0000000000..1477980aeb --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_attitude.h @@ -0,0 +1,182 @@ +// MESSAGE ATTITUDE PACKING + +#define MAVLINK_MSG_ID_ATTITUDE 30 + +typedef struct __mavlink_attitude_t +{ + uint64_t usec; ///< Timestamp (microseconds) + float 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) + +} mavlink_attitude_t; + + + +/** + * @brief Send a attitude message + * + * @param usec Timestamp (microseconds) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; + + i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds) + i += put_float_by_index(roll, i, msg->payload); //Roll angle (rad) + i += put_float_by_index(pitch, i, msg->payload); //Pitch angle (rad) + i += put_float_by_index(yaw, i, msg->payload); //Yaw angle (rad) + i += put_float_by_index(rollspeed, i, msg->payload); //Roll angular speed (rad/s) + i += put_float_by_index(pitchspeed, i, msg->payload); //Pitch angular speed (rad/s) + i += put_float_by_index(yawspeed, i, msg->payload); //Yaw angular speed (rad/s) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude) +{ + return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->usec, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ + mavlink_message_t msg; + mavlink_msg_attitude_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ATTITUDE UNPACKING + +/** + * @brief Get field usec from attitude message + * + * @return Timestamp (microseconds) + */ +static inline uint64_t mavlink_msg_attitude_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field roll from attitude message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from attitude message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from attitude message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field rollspeed from attitude message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitchspeed from attitude message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yawspeed from attitude message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude) +{ + attitude->usec = mavlink_msg_attitude_get_usec(msg); + attitude->roll = mavlink_msg_attitude_get_roll(msg); + attitude->pitch = mavlink_msg_attitude_get_pitch(msg); + attitude->yaw = mavlink_msg_attitude_get_yaw(msg); + attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg); + attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); + attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_attitude_controller_output.h b/libraries/mavlink/include/common/mavlink_msg_attitude_controller_output.h new file mode 100644 index 0000000000..5393eda98a --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_attitude_controller_output.h @@ -0,0 +1,115 @@ +// MESSAGE ATTITUDE_CONTROLLER_OUTPUT PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT 60 + +typedef struct __mavlink_attitude_controller_output_t +{ + uint8_t enabled; ///< 1: enabled, 0: disabled + int8_t roll; ///< Attitude roll: -128: -100%, 127: +100% + int8_t pitch; ///< Attitude pitch: -128: -100%, 127: +100% + int8_t yaw; ///< Attitude yaw: -128: -100%, 127: +100% + int8_t thrust; ///< Attitude thrust: -128: -100%, 127: +100% + +} mavlink_attitude_controller_output_t; + + + +/** + * @brief Send a attitude_controller_output message + * + * @param enabled 1: enabled, 0: disabled + * @param roll Attitude roll: -128: -100%, 127: +100% + * @param pitch Attitude pitch: -128: -100%, 127: +100% + * @param yaw Attitude yaw: -128: -100%, 127: +100% + * @param thrust Attitude thrust: -128: -100%, 127: +100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t enabled, int8_t roll, int8_t pitch, int8_t yaw, int8_t thrust) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT; + + i += put_uint8_t_by_index(enabled, i, msg->payload); //1: enabled, 0: disabled + i += put_int8_t_by_index(roll, i, msg->payload); //Attitude roll: -128: -100%, 127: +100% + i += put_int8_t_by_index(pitch, i, msg->payload); //Attitude pitch: -128: -100%, 127: +100% + i += put_int8_t_by_index(yaw, i, msg->payload); //Attitude yaw: -128: -100%, 127: +100% + i += put_int8_t_by_index(thrust, i, msg->payload); //Attitude thrust: -128: -100%, 127: +100% + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_attitude_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_controller_output_t* attitude_controller_output) +{ + return mavlink_msg_attitude_controller_output_pack(system_id, component_id, msg, attitude_controller_output->enabled, attitude_controller_output->roll, attitude_controller_output->pitch, attitude_controller_output->yaw, attitude_controller_output->thrust); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_controller_output_send(mavlink_channel_t chan, uint8_t enabled, int8_t roll, int8_t pitch, int8_t yaw, int8_t thrust) +{ + mavlink_message_t msg; + mavlink_msg_attitude_controller_output_pack(mavlink_system.sysid, mavlink_system.compid, &msg, enabled, roll, pitch, yaw, thrust); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ATTITUDE_CONTROLLER_OUTPUT UNPACKING + +/** + * @brief Get field enabled from attitude_controller_output message + * + * @return 1: enabled, 0: disabled + */ +static inline uint8_t mavlink_msg_attitude_controller_output_get_enabled(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field roll from attitude_controller_output message + * + * @return Attitude roll: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_attitude_controller_output_get_roll(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field pitch from attitude_controller_output message + * + * @return Attitude pitch: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_attitude_controller_output_get_pitch(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t))[0]; +} + +/** + * @brief Get field yaw from attitude_controller_output message + * + * @return Attitude yaw: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_attitude_controller_output_get_yaw(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t)+sizeof(int8_t))[0]; +} + +/** + * @brief Get field thrust from attitude_controller_output message + * + * @return Attitude thrust: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_attitude_controller_output_get_thrust(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t)+sizeof(int8_t)+sizeof(int8_t))[0]; +} + +static inline void mavlink_msg_attitude_controller_output_decode(const mavlink_message_t* msg, mavlink_attitude_controller_output_t* attitude_controller_output) +{ + attitude_controller_output->enabled = mavlink_msg_attitude_controller_output_get_enabled(msg); + attitude_controller_output->roll = mavlink_msg_attitude_controller_output_get_roll(msg); + attitude_controller_output->pitch = mavlink_msg_attitude_controller_output_get_pitch(msg); + attitude_controller_output->yaw = mavlink_msg_attitude_controller_output_get_yaw(msg); + attitude_controller_output->thrust = mavlink_msg_attitude_controller_output_get_thrust(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_boot.h b/libraries/mavlink/include/common/mavlink_msg_boot.h new file mode 100644 index 0000000000..4a4fe06523 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_boot.h @@ -0,0 +1,64 @@ +// MESSAGE BOOT PACKING + +#define MAVLINK_MSG_ID_BOOT 1 + +typedef struct __mavlink_boot_t +{ + uint32_t version; ///< The onboard software version + +} mavlink_boot_t; + + + +/** + * @brief Send a boot message + * + * @param version The onboard software version + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t version) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_BOOT; + + i += put_uint32_t_by_index(version, i, msg->payload); //The onboard software version + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_boot_t* boot) +{ + return mavlink_msg_boot_pack(system_id, component_id, msg, boot->version); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t version) +{ + mavlink_message_t msg; + mavlink_msg_boot_pack(mavlink_system.sysid, mavlink_system.compid, &msg, version); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE BOOT UNPACKING + +/** + * @brief Get field version from boot message + * + * @return The onboard software version + */ +static inline uint32_t mavlink_msg_boot_get_version(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload)[0]; + r.b[2] = (msg->payload)[1]; + r.b[1] = (msg->payload)[2]; + r.b[0] = (msg->payload)[3]; + return (uint32_t)r.i; +} + +static inline void mavlink_msg_boot_decode(const mavlink_message_t* msg, mavlink_boot_t* boot) +{ + boot->version = mavlink_msg_boot_get_version(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_debug.h b/libraries/mavlink/include/common/mavlink_msg_debug.h new file mode 100644 index 0000000000..a053751b74 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_debug.h @@ -0,0 +1,78 @@ +// MESSAGE DEBUG PACKING + +#define MAVLINK_MSG_ID_DEBUG 255 + +typedef struct __mavlink_debug_t +{ + uint8_t ind; ///< index of debug variable + float value; ///< DEBUG value + +} mavlink_debug_t; + + + +/** + * @brief Send a debug message + * + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t ind, float value) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_DEBUG; + + i += put_uint8_t_by_index(ind, i, msg->payload); //index of debug variable + i += put_float_by_index(value, i, msg->payload); //DEBUG value + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug) +{ + return mavlink_msg_debug_pack(system_id, component_id, msg, debug->ind, debug->value); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, float value) +{ + mavlink_message_t msg; + mavlink_msg_debug_pack(mavlink_system.sysid, mavlink_system.compid, &msg, ind, value); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE DEBUG UNPACKING + +/** + * @brief Get field ind from debug message + * + * @return index of debug variable + */ +static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field value from debug message + * + * @return DEBUG value + */ +static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug) +{ + debug->ind = mavlink_msg_debug_get_ind(msg); + debug->value = mavlink_msg_debug_get_value(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_global_position.h b/libraries/mavlink/include/common/mavlink_msg_global_position.h new file mode 100644 index 0000000000..f106d531e0 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_global_position.h @@ -0,0 +1,182 @@ +// MESSAGE GLOBAL_POSITION PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION 33 + +typedef struct __mavlink_global_position_t +{ + uint64_t usec; ///< Timestamp (microseconds since unix epoch) + float lat; ///< X Position + float lon; ///< Y Position + float alt; ///< Z Position + float vx; ///< X Speed + float vy; ///< Y Speed + float vz; ///< Z Speed + +} mavlink_global_position_t; + + + +/** + * @brief Send a global_position message + * + * @param usec Timestamp (microseconds since unix epoch) + * @param lat X Position + * @param lon Y Position + * @param alt Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION; + + i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch) + i += put_float_by_index(lat, i, msg->payload); //X Position + i += put_float_by_index(lon, i, msg->payload); //Y Position + i += put_float_by_index(alt, i, msg->payload); //Z Position + i += put_float_by_index(vx, i, msg->payload); //X Speed + i += put_float_by_index(vy, i, msg->payload); //Y Speed + i += put_float_by_index(vz, i, msg->payload); //Z Speed + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position) +{ + return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz) +{ + mavlink_message_t msg; + mavlink_msg_global_position_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, lat, lon, alt, vx, vy, vz); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GLOBAL_POSITION UNPACKING + +/** + * @brief Get field usec from global_position message + * + * @return Timestamp (microseconds since unix epoch) + */ +static inline uint64_t mavlink_msg_global_position_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field lat from global_position message + * + * @return X Position + */ +static inline float mavlink_msg_global_position_get_lat(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field lon from global_position message + * + * @return Y Position + */ +static inline float mavlink_msg_global_position_get_lon(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field alt from global_position message + * + * @return Z Position + */ +static inline float mavlink_msg_global_position_get_alt(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vx from global_position message + * + * @return X Speed + */ +static inline float mavlink_msg_global_position_get_vx(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vy from global_position message + * + * @return Y Speed + */ +static inline float mavlink_msg_global_position_get_vy(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vz from global_position message + * + * @return Z Speed + */ +static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position) +{ + global_position->usec = mavlink_msg_global_position_get_usec(msg); + global_position->lat = mavlink_msg_global_position_get_lat(msg); + global_position->lon = mavlink_msg_global_position_get_lon(msg); + global_position->alt = mavlink_msg_global_position_get_alt(msg); + global_position->vx = mavlink_msg_global_position_get_vx(msg); + global_position->vy = mavlink_msg_global_position_get_vy(msg); + global_position->vz = mavlink_msg_global_position_get_vz(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_gps_raw.h b/libraries/mavlink/include/common/mavlink_msg_gps_raw.h new file mode 100644 index 0000000000..703d96663c --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_gps_raw.h @@ -0,0 +1,215 @@ +// MESSAGE GPS_RAW PACKING + +#define MAVLINK_MSG_ID_GPS_RAW 32 + +typedef struct __mavlink_gps_raw_t +{ + uint64_t usec; ///< Timestamp (microseconds since unix epoch) + uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix + float lat; ///< X Position + float lon; ///< Y Position + float alt; ///< Z Position in meters + float eph; ///< Uncertainty in meters of latitude + float epv; ///< Uncertainty in meters of longitude + float v; ///< Overall speed + float hdg; ///< Heading, in FIXME + +} mavlink_gps_raw_t; + + + +/** + * @brief Send a gps_raw message + * + * @param usec Timestamp (microseconds since unix epoch) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix + * @param lat X Position + * @param lon Y Position + * @param alt Z Position in meters + * @param eph Uncertainty in meters of latitude + * @param epv Uncertainty in meters of longitude + * @param v Overall speed + * @param hdg Heading, in FIXME + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_RAW; + + i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch) + i += put_uint8_t_by_index(fix_type, i, msg->payload); //0-1: no fix, 2: 2D fix, 3: 3D fix + i += put_float_by_index(lat, i, msg->payload); //X Position + i += put_float_by_index(lon, i, msg->payload); //Y Position + i += put_float_by_index(alt, i, msg->payload); //Z Position in meters + i += put_float_by_index(eph, i, msg->payload); //Uncertainty in meters of latitude + i += put_float_by_index(epv, i, msg->payload); //Uncertainty in meters of longitude + i += put_float_by_index(v, i, msg->payload); //Overall speed + i += put_float_by_index(hdg, i, msg->payload); //Heading, in FIXME + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw) +{ + return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg) +{ + mavlink_message_t msg; + mavlink_msg_gps_raw_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, fix_type, lat, lon, alt, eph, epv, v, hdg); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GPS_RAW UNPACKING + +/** + * @brief Get field usec from gps_raw message + * + * @return Timestamp (microseconds since unix epoch) + */ +static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field fix_type from gps_raw message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix + */ +static inline uint8_t mavlink_msg_gps_raw_get_fix_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint64_t))[0]; +} + +/** + * @brief Get field lat from gps_raw message + * + * @return X Position + */ +static inline float mavlink_msg_gps_raw_get_lat(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field lon from gps_raw message + * + * @return Y Position + */ +static inline float mavlink_msg_gps_raw_get_lon(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field alt from gps_raw message + * + * @return Z Position in meters + */ +static inline float mavlink_msg_gps_raw_get_alt(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field eph from gps_raw message + * + * @return Uncertainty in meters of latitude + */ +static inline float mavlink_msg_gps_raw_get_eph(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field epv from gps_raw message + * + * @return Uncertainty in meters of longitude + */ +static inline float mavlink_msg_gps_raw_get_epv(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field v from gps_raw message + * + * @return Overall speed + */ +static inline float mavlink_msg_gps_raw_get_v(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field hdg from gps_raw message + * + * @return Heading, in FIXME + */ +static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw) +{ + gps_raw->usec = mavlink_msg_gps_raw_get_usec(msg); + gps_raw->fix_type = mavlink_msg_gps_raw_get_fix_type(msg); + gps_raw->lat = mavlink_msg_gps_raw_get_lat(msg); + gps_raw->lon = mavlink_msg_gps_raw_get_lon(msg); + gps_raw->alt = mavlink_msg_gps_raw_get_alt(msg); + gps_raw->eph = mavlink_msg_gps_raw_get_eph(msg); + gps_raw->epv = mavlink_msg_gps_raw_get_epv(msg); + gps_raw->v = mavlink_msg_gps_raw_get_v(msg); + gps_raw->hdg = mavlink_msg_gps_raw_get_hdg(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_gps_status.h b/libraries/mavlink/include/common/mavlink_msg_gps_status.h new file mode 100644 index 0000000000..0b99d1bce3 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_gps_status.h @@ -0,0 +1,144 @@ +// MESSAGE GPS_STATUS PACKING + +#define MAVLINK_MSG_ID_GPS_STATUS 27 + +typedef struct __mavlink_gps_status_t +{ + uint8_t satellites_visible; ///< Number of satellites visible + int8_t satellite_prn[20]; ///< Global satellite ID + int8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization + int8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite + int8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg. + int8_t satellite_snr[20]; ///< Signal to noise ratio of satellite + +} mavlink_gps_status_t; + +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 + + +/** + * @brief Send a gps_status message + * + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; + + i += put_uint8_t_by_index(satellites_visible, i, msg->payload); //Number of satellites visible + i += put_array_by_index(satellite_prn, 20, i, msg->payload); //Global satellite ID + i += put_array_by_index(satellite_used, 20, i, msg->payload); //0: Satellite not used, 1: used for localization + i += put_array_by_index(satellite_elevation, 20, i, msg->payload); //Elevation (0: right on top of receiver, 90: on the horizon) of satellite + i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); //Direction of satellite, 0: 0 deg, 255: 360 deg. + i += put_array_by_index(satellite_snr, 20, i, msg->payload); //Signal to noise ratio of satellite + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) +{ + return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr) +{ + mavlink_message_t msg; + mavlink_msg_gps_status_pack(mavlink_system.sysid, mavlink_system.compid, &msg, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GPS_STATUS UNPACKING + +/** + * @brief Get field satellites_visible from gps_status message + * + * @return Number of satellites visible + */ +static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field satellite_prn from gps_status message + * + * @return Global satellite ID + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t), 20); + return 20; +} + +/** + * @brief Get field satellite_used from gps_status message + * + * @return 0: Satellite not used, 1: used for localization + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+20, 20); + return 20; +} + +/** + * @brief Get field satellite_elevation from gps_status message + * + * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20, 20); + return 20; +} + +/** + * @brief Get field satellite_azimuth from gps_status message + * + * @return Direction of satellite, 0: 0 deg, 255: 360 deg. + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20+20, 20); + return 20; +} + +/** + * @brief Get field satellite_snr from gps_status message + * + * @return Signal to noise ratio of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20+20+20, 20); + return 20; +} + +static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status) +{ + gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg); + mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn); + mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used); + mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation); + mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth); + mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_heartbeat.h b/libraries/mavlink/include/common/mavlink_msg_heartbeat.h new file mode 100644 index 0000000000..3d56fe7ac0 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_heartbeat.h @@ -0,0 +1,73 @@ +// MESSAGE HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_HEARTBEAT 0 + +typedef struct __mavlink_heartbeat_t +{ + uint8_t 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 + +} mavlink_heartbeat_t; + + + +/** + * @brief Send a heartbeat message + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t autopilot) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + + i += put_uint8_t_by_index(type, i, msg->payload); //Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + i += put_uint8_t_by_index(autopilot, i, msg->payload); //Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) +{ + return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot) +{ + mavlink_message_t msg; + mavlink_msg_heartbeat_pack(mavlink_system.sysid, mavlink_system.compid, &msg, type, autopilot); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE HEARTBEAT UNPACKING + +/** + * @brief Get field type from heartbeat message + * + * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + */ +static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field autopilot from heartbeat message + * + * @return Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) +{ + heartbeat->type = mavlink_msg_heartbeat_get_type(msg); + heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_local_position.h b/libraries/mavlink/include/common/mavlink_msg_local_position.h new file mode 100644 index 0000000000..efafeac833 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_local_position.h @@ -0,0 +1,182 @@ +// MESSAGE LOCAL_POSITION PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION 31 + +typedef struct __mavlink_local_position_t +{ + uint64_t usec; ///< Timestamp (microseconds since unix epoch) + float x; ///< X Position + float y; ///< Y Position + float z; ///< Z Position + float vx; ///< X Speed + float vy; ///< Y Speed + float vz; ///< Z Speed + +} mavlink_local_position_t; + + + +/** + * @brief Send a local_position message + * + * @param usec Timestamp (microseconds since unix epoch) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float vx, float vy, float vz) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION; + + i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch) + i += put_float_by_index(x, i, msg->payload); //X Position + i += put_float_by_index(y, i, msg->payload); //Y Position + i += put_float_by_index(z, i, msg->payload); //Z Position + i += put_float_by_index(vx, i, msg->payload); //X Speed + i += put_float_by_index(vy, i, msg->payload); //Y Speed + i += put_float_by_index(vz, i, msg->payload); //Z Speed + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_local_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_t* local_position) +{ + return mavlink_msg_local_position_pack(system_id, component_id, msg, local_position->usec, local_position->x, local_position->y, local_position->z, local_position->vx, local_position->vy, local_position->vz); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float vx, float vy, float vz) +{ + mavlink_message_t msg; + mavlink_msg_local_position_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, x, y, z, vx, vy, vz); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE LOCAL_POSITION UNPACKING + +/** + * @brief Get field usec from local_position message + * + * @return Timestamp (microseconds since unix epoch) + */ +static inline uint64_t mavlink_msg_local_position_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field x from local_position message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from local_position message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from local_position message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vx from local_position message + * + * @return X Speed + */ +static inline float mavlink_msg_local_position_get_vx(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vy from local_position message + * + * @return Y Speed + */ +static inline float mavlink_msg_local_position_get_vy(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vz from local_position message + * + * @return Z Speed + */ +static inline float mavlink_msg_local_position_get_vz(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_local_position_decode(const mavlink_message_t* msg, mavlink_local_position_t* local_position) +{ + local_position->usec = mavlink_msg_local_position_get_usec(msg); + local_position->x = mavlink_msg_local_position_get_x(msg); + local_position->y = mavlink_msg_local_position_get_y(msg); + local_position->z = mavlink_msg_local_position_get_z(msg); + local_position->vx = mavlink_msg_local_position_get_vx(msg); + local_position->vy = mavlink_msg_local_position_get_vy(msg); + local_position->vz = mavlink_msg_local_position_get_vz(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_local_position_setpoint.h b/libraries/mavlink/include/common/mavlink_msg_local_position_setpoint.h new file mode 100644 index 0000000000..5a580949ab --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_local_position_setpoint.h @@ -0,0 +1,121 @@ +// MESSAGE LOCAL_POSITION_SETPOINT PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51 + +typedef struct __mavlink_local_position_setpoint_t +{ + float x; ///< x position 1 + float y; ///< y position 1 + float z; ///< z position 1 + float yaw; ///< x position 2 + +} mavlink_local_position_setpoint_t; + + + +/** + * @brief Send a local_position_setpoint message + * + * @param x x position 1 + * @param y y position 1 + * @param z z position 1 + * @param yaw x position 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; + + i += put_float_by_index(x, i, msg->payload); //x position 1 + i += put_float_by_index(y, i, msg->payload); //y position 1 + i += put_float_by_index(z, i, msg->payload); //z position 1 + i += put_float_by_index(yaw, i, msg->payload); //x position 2 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint) +{ + return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_local_position_setpoint_pack(mavlink_system.sysid, mavlink_system.compid, &msg, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING + +/** + * @brief Get field x from local_position_setpoint message + * + * @return x position 1 + */ +static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload)[0]; + r.b[2] = (msg->payload)[1]; + r.b[1] = (msg->payload)[2]; + r.b[0] = (msg->payload)[3]; + return (float)r.f; +} + +/** + * @brief Get field y from local_position_setpoint message + * + * @return y position 1 + */ +static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from local_position_setpoint message + * + * @return z position 1 + */ +static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from local_position_setpoint message + * + * @return x position 2 + */ +static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_t* local_position_setpoint) +{ + local_position_setpoint->x = mavlink_msg_local_position_setpoint_get_x(msg); + local_position_setpoint->y = mavlink_msg_local_position_setpoint_get_y(msg); + local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg); + local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_local_position_setpoint_set.h b/libraries/mavlink/include/common/mavlink_msg_local_position_setpoint_set.h new file mode 100644 index 0000000000..b638c6dd6f --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_local_position_setpoint_set.h @@ -0,0 +1,149 @@ +// MESSAGE LOCAL_POSITION_SETPOINT_SET PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET 50 + +typedef struct __mavlink_local_position_setpoint_set_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + float x; ///< x position 1 + float y; ///< y position 1 + float z; ///< z position 1 + float yaw; ///< x position 2 + +} mavlink_local_position_setpoint_set_t; + + + +/** + * @brief Send a local_position_setpoint_set message + * + * @param target_system System ID + * @param target_component Component ID + * @param x x position 1 + * @param y y position 1 + * @param z z position 1 + * @param yaw x position 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_float_by_index(x, i, msg->payload); //x position 1 + i += put_float_by_index(y, i, msg->payload); //y position 1 + i += put_float_by_index(z, i, msg->payload); //z position 1 + i += put_float_by_index(yaw, i, msg->payload); //x position 2 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_local_position_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_set_t* local_position_setpoint_set) +{ + return mavlink_msg_local_position_setpoint_set_pack(system_id, component_id, msg, local_position_setpoint_set->target_system, local_position_setpoint_set->target_component, local_position_setpoint_set->x, local_position_setpoint_set->y, local_position_setpoint_set->z, local_position_setpoint_set->yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_local_position_setpoint_set_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE LOCAL_POSITION_SETPOINT_SET UNPACKING + +/** + * @brief Get field target_system from local_position_setpoint_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from local_position_setpoint_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field x from local_position_setpoint_set message + * + * @return x position 1 + */ +static inline float mavlink_msg_local_position_setpoint_set_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from local_position_setpoint_set message + * + * @return y position 1 + */ +static inline float mavlink_msg_local_position_setpoint_set_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from local_position_setpoint_set message + * + * @return z position 1 + */ +static inline float mavlink_msg_local_position_setpoint_set_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from local_position_setpoint_set message + * + * @return x position 2 + */ +static inline float mavlink_msg_local_position_setpoint_set_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_local_position_setpoint_set_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_set_t* local_position_setpoint_set) +{ + local_position_setpoint_set->target_system = mavlink_msg_local_position_setpoint_set_get_target_system(msg); + local_position_setpoint_set->target_component = mavlink_msg_local_position_setpoint_set_get_target_component(msg); + local_position_setpoint_set->x = mavlink_msg_local_position_setpoint_set_get_x(msg); + local_position_setpoint_set->y = mavlink_msg_local_position_setpoint_set_get_y(msg); + local_position_setpoint_set->z = mavlink_msg_local_position_setpoint_set_get_z(msg); + local_position_setpoint_set->yaw = mavlink_msg_local_position_setpoint_set_get_yaw(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_manual_control.h b/libraries/mavlink/include/common/mavlink_msg_manual_control.h new file mode 100644 index 0000000000..4c503511f1 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_manual_control.h @@ -0,0 +1,191 @@ +// MESSAGE MANUAL_CONTROL PACKING + +#define MAVLINK_MSG_ID_MANUAL_CONTROL 69 + +typedef struct __mavlink_manual_control_t +{ + uint8_t target; ///< The system to be controlled + float roll; ///< roll + float pitch; ///< pitch + float yaw; ///< yaw + float thrust; ///< thrust + uint8_t 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 + +} mavlink_manual_control_t; + + + +/** + * @brief Send a manual_control message + * + * @param target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system to be controlled + i += put_float_by_index(roll, i, msg->payload); //roll + i += put_float_by_index(pitch, i, msg->payload); //pitch + i += put_float_by_index(yaw, i, msg->payload); //yaw + i += put_float_by_index(thrust, i, msg->payload); //thrust + i += put_uint8_t_by_index(roll_manual, i, msg->payload); //roll control enabled auto:0, manual:1 + i += put_uint8_t_by_index(pitch_manual, i, msg->payload); //pitch auto:0, manual:1 + i += put_uint8_t_by_index(yaw_manual, i, msg->payload); //yaw auto:0, manual:1 + i += put_uint8_t_by_index(thrust_manual, i, msg->payload); //thrust auto:0, manual:1 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) +{ + return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->roll, manual_control->pitch, manual_control->yaw, manual_control->thrust, manual_control->roll_manual, manual_control->pitch_manual, manual_control->yaw_manual, manual_control->thrust_manual); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ + mavlink_message_t msg; + mavlink_msg_manual_control_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE MANUAL_CONTROL UNPACKING + +/** + * @brief Get field target from manual_control message + * + * @return The system to be controlled + */ +static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field roll from manual_control message + * + * @return roll + */ +static inline float mavlink_msg_manual_control_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from manual_control message + * + * @return pitch + */ +static inline float mavlink_msg_manual_control_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from manual_control message + * + * @return yaw + */ +static inline float mavlink_msg_manual_control_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field thrust from manual_control message + * + * @return thrust + */ +static inline float mavlink_msg_manual_control_get_thrust(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field roll_manual from manual_control message + * + * @return roll control enabled auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_roll_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; +} + +/** + * @brief Get field pitch_manual from manual_control message + * + * @return pitch auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_pitch_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field yaw_manual from manual_control message + * + * @return yaw auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_yaw_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field thrust_manual from manual_control message + * + * @return thrust auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_thrust_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control) +{ + manual_control->target = mavlink_msg_manual_control_get_target(msg); + manual_control->roll = mavlink_msg_manual_control_get_roll(msg); + manual_control->pitch = mavlink_msg_manual_control_get_pitch(msg); + manual_control->yaw = mavlink_msg_manual_control_get_yaw(msg); + manual_control->thrust = mavlink_msg_manual_control_get_thrust(msg); + manual_control->roll_manual = mavlink_msg_manual_control_get_roll_manual(msg); + manual_control->pitch_manual = mavlink_msg_manual_control_get_pitch_manual(msg); + manual_control->yaw_manual = mavlink_msg_manual_control_get_yaw_manual(msg); + manual_control->thrust_manual = mavlink_msg_manual_control_get_thrust_manual(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_param_request_list.h b/libraries/mavlink/include/common/mavlink_msg_param_request_list.h new file mode 100644 index 0000000000..0bba5a5741 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_param_request_list.h @@ -0,0 +1,73 @@ +// MESSAGE PARAM_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 + +typedef struct __mavlink_param_request_list_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + +} mavlink_param_request_list_t; + + + +/** + * @brief Send a param_request_list message + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) +{ + return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ + mavlink_message_t msg; + mavlink_msg_param_request_list_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PARAM_REQUEST_LIST UNPACKING + +/** + * @brief Get field target_system from param_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from param_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list) +{ + param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg); + param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_param_request_read.h b/libraries/mavlink/include/common/mavlink_msg_param_request_read.h new file mode 100644 index 0000000000..a8391b0d5f --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_param_request_read.h @@ -0,0 +1,107 @@ +// MESSAGE PARAM_REQUEST_READ PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 + +typedef struct __mavlink_param_request_read_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + int8_t param_id[15]; ///< Onboard parameter id + uint16_t param_index; ///< Parameter index + +} mavlink_param_request_read_t; + +#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 15 + + +/** + * @brief Send a param_request_read message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_index Parameter index + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, uint16_t param_index) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id + i += put_uint16_t_by_index(param_index, i, msg->payload); //Parameter index + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) +{ + return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, uint16_t param_index) +{ + mavlink_message_t msg; + mavlink_msg_param_request_read_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, param_id, param_index); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PARAM_REQUEST_READ UNPACKING + +/** + * @brief Get field target_system from param_request_read message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from param_request_read message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field param_id from param_request_read message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t), 15); + return 15; +} + +/** + * @brief Get field param_index from param_request_read message + * + * @return Parameter index + */ +static inline uint16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read) +{ + param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg); + param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg); + mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id); + param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_param_set.h b/libraries/mavlink/include/common/mavlink_msg_param_set.h new file mode 100644 index 0000000000..5dbd097394 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_param_set.h @@ -0,0 +1,109 @@ +// MESSAGE PARAM_SET PACKING + +#define MAVLINK_MSG_ID_PARAM_SET 23 + +typedef struct __mavlink_param_set_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + int8_t param_id[15]; ///< Onboard parameter id + float param_value; ///< Onboard parameter value + +} mavlink_param_set_t; + +#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 15 + + +/** + * @brief Send a param_set message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, float param_value) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id + i += put_float_by_index(param_value, i, msg->payload); //Onboard parameter value + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set) +{ + return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, float param_value) +{ + mavlink_message_t msg; + mavlink_msg_param_set_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, param_id, param_value); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PARAM_SET UNPACKING + +/** + * @brief Get field target_system from param_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from param_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field param_id from param_set message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t), 15); + return 15; +} + +/** + * @brief Get field param_value from param_set message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[3]; + return (float)r.f; +} + +static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set) +{ + param_set->target_system = mavlink_msg_param_set_get_target_system(msg); + param_set->target_component = mavlink_msg_param_set_get_target_component(msg); + mavlink_msg_param_set_get_param_id(msg, param_set->param_id); + param_set->param_value = mavlink_msg_param_set_get_param_value(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_param_value.h b/libraries/mavlink/include/common/mavlink_msg_param_value.h new file mode 100644 index 0000000000..911e0de354 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_param_value.h @@ -0,0 +1,115 @@ +// MESSAGE PARAM_VALUE PACKING + +#define MAVLINK_MSG_ID_PARAM_VALUE 22 + +typedef struct __mavlink_param_value_t +{ + int8_t param_id[15]; ///< Onboard parameter id + float param_value; ///< Onboard parameter value + uint16_t param_count; ///< Total number of onboard parameters + uint16_t param_index; ///< Index of this onboard parameter + +} mavlink_param_value_t; + +#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 15 + + +/** + * @brief Send a param_value message + * + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; + + i += put_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id + i += put_float_by_index(param_value, i, msg->payload); //Onboard parameter value + i += put_uint16_t_by_index(param_count, i, msg->payload); //Total number of onboard parameters + i += put_uint16_t_by_index(param_index, i, msg->payload); //Index of this onboard parameter + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value) +{ + return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_count, param_value->param_index); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index) +{ + mavlink_message_t msg; + mavlink_msg_param_value_pack(mavlink_system.sysid, mavlink_system.compid, &msg, param_id, param_value, param_count, param_index); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PARAM_VALUE UNPACKING + +/** + * @brief Get field param_id from param_value message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload, 15); + return 15; +} + +/** + * @brief Get field param_value from param_value message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+15)[0]; + r.b[2] = (msg->payload+15)[1]; + r.b[1] = (msg->payload+15)[2]; + r.b[0] = (msg->payload+15)[3]; + return (float)r.f; +} + +/** + * @brief Get field param_count from param_value message + * + * @return Total number of onboard parameters + */ +static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+15+sizeof(float))[0]; + r.b[0] = (msg->payload+15+sizeof(float))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field param_index from param_value message + * + * @return Index of this onboard parameter + */ +static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+15+sizeof(float)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+15+sizeof(float)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value) +{ + mavlink_msg_param_value_get_param_id(msg, param_value->param_id); + param_value->param_value = mavlink_msg_param_value_get_param_value(msg); + param_value->param_count = mavlink_msg_param_value_get_param_count(msg); + param_value->param_index = mavlink_msg_param_value_get_param_index(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_ping.h b/libraries/mavlink/include/common/mavlink_msg_ping.h new file mode 100644 index 0000000000..0117d8fd85 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_ping.h @@ -0,0 +1,115 @@ +// MESSAGE PING PACKING + +#define MAVLINK_MSG_ID_PING 3 + +typedef struct __mavlink_ping_t +{ + uint32_t seq; ///< PING sequence + uint8_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 + uint64_t time; ///< Unix timestamp in microseconds + +} mavlink_ping_t; + + + +/** + * @brief Send a ping message + * + * @param seq PING sequence + * @param 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 + * @param 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 + * @param time Unix timestamp in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PING; + + i += put_uint32_t_by_index(seq, i, msg->payload); //PING sequence + i += put_uint8_t_by_index(target_system, i, msg->payload); //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 + i += put_uint8_t_by_index(target_component, i, msg->payload); //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 + i += put_uint64_t_by_index(time, i, msg->payload); //Unix timestamp in microseconds + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping) +{ + return mavlink_msg_ping_pack(system_id, component_id, msg, ping->seq, ping->target_system, ping->target_component, ping->time); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time) +{ + mavlink_message_t msg; + mavlink_msg_ping_pack(mavlink_system.sysid, mavlink_system.compid, &msg, seq, target_system, target_component, time); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PING UNPACKING + +/** + * @brief Get field seq from ping message + * + * @return PING sequence + */ +static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload)[0]; + r.b[2] = (msg->payload)[1]; + r.b[1] = (msg->payload)[2]; + r.b[0] = (msg->payload)[3]; + return (uint32_t)r.i; +} + +/** + * @brief Get field target_system from ping message + * + * @return 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 + */ +static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint32_t))[0]; +} + +/** + * @brief Get field target_component from ping message + * + * @return 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 + */ +static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint32_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field time from ping message + * + * @return Unix timestamp in microseconds + */ +static inline uint64_t mavlink_msg_ping_get_time(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[6] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[5] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[4] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[3]; + r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[4]; + r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[5]; + r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[6]; + r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[7]; + return (uint64_t)r.ll; +} + +static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping) +{ + ping->seq = mavlink_msg_ping_get_seq(msg); + ping->target_system = mavlink_msg_ping_get_target_system(msg); + ping->target_component = mavlink_msg_ping_get_target_component(msg); + ping->time = mavlink_msg_ping_get_time(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_position_controller_output.h b/libraries/mavlink/include/common/mavlink_msg_position_controller_output.h new file mode 100644 index 0000000000..5b0fbb2660 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_position_controller_output.h @@ -0,0 +1,115 @@ +// MESSAGE POSITION_CONTROLLER_OUTPUT PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT 61 + +typedef struct __mavlink_position_controller_output_t +{ + uint8_t enabled; ///< 1: enabled, 0: disabled + int8_t x; ///< Position x: -128: -100%, 127: +100% + int8_t y; ///< Position y: -128: -100%, 127: +100% + int8_t z; ///< Position z: -128: -100%, 127: +100% + int8_t yaw; ///< Position yaw: -128: -100%, 127: +100% + +} mavlink_position_controller_output_t; + + + +/** + * @brief Send a position_controller_output message + * + * @param enabled 1: enabled, 0: disabled + * @param x Position x: -128: -100%, 127: +100% + * @param y Position y: -128: -100%, 127: +100% + * @param z Position z: -128: -100%, 127: +100% + * @param yaw Position yaw: -128: -100%, 127: +100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t enabled, int8_t x, int8_t y, int8_t z, int8_t yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT; + + i += put_uint8_t_by_index(enabled, i, msg->payload); //1: enabled, 0: disabled + i += put_int8_t_by_index(x, i, msg->payload); //Position x: -128: -100%, 127: +100% + i += put_int8_t_by_index(y, i, msg->payload); //Position y: -128: -100%, 127: +100% + i += put_int8_t_by_index(z, i, msg->payload); //Position z: -128: -100%, 127: +100% + i += put_int8_t_by_index(yaw, i, msg->payload); //Position yaw: -128: -100%, 127: +100% + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_position_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_controller_output_t* position_controller_output) +{ + return mavlink_msg_position_controller_output_pack(system_id, component_id, msg, position_controller_output->enabled, position_controller_output->x, position_controller_output->y, position_controller_output->z, position_controller_output->yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_controller_output_send(mavlink_channel_t chan, uint8_t enabled, int8_t x, int8_t y, int8_t z, int8_t yaw) +{ + mavlink_message_t msg; + mavlink_msg_position_controller_output_pack(mavlink_system.sysid, mavlink_system.compid, &msg, enabled, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POSITION_CONTROLLER_OUTPUT UNPACKING + +/** + * @brief Get field enabled from position_controller_output message + * + * @return 1: enabled, 0: disabled + */ +static inline uint8_t mavlink_msg_position_controller_output_get_enabled(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field x from position_controller_output message + * + * @return Position x: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_position_controller_output_get_x(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field y from position_controller_output message + * + * @return Position y: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_position_controller_output_get_y(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t))[0]; +} + +/** + * @brief Get field z from position_controller_output message + * + * @return Position z: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_position_controller_output_get_z(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t)+sizeof(int8_t))[0]; +} + +/** + * @brief Get field yaw from position_controller_output message + * + * @return Position yaw: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_position_controller_output_get_yaw(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t)+sizeof(int8_t)+sizeof(int8_t))[0]; +} + +static inline void mavlink_msg_position_controller_output_decode(const mavlink_message_t* msg, mavlink_position_controller_output_t* position_controller_output) +{ + position_controller_output->enabled = mavlink_msg_position_controller_output_get_enabled(msg); + position_controller_output->x = mavlink_msg_position_controller_output_get_x(msg); + position_controller_output->y = mavlink_msg_position_controller_output_get_y(msg); + position_controller_output->z = mavlink_msg_position_controller_output_get_z(msg); + position_controller_output->yaw = mavlink_msg_position_controller_output_get_yaw(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_position_target.h b/libraries/mavlink/include/common/mavlink_msg_position_target.h new file mode 100644 index 0000000000..42d64c50eb --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_position_target.h @@ -0,0 +1,121 @@ +// MESSAGE POSITION_TARGET PACKING + +#define MAVLINK_MSG_ID_POSITION_TARGET 63 + +typedef struct __mavlink_position_target_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< yaw orientation in radians, 0 = NORTH + +} mavlink_position_target_t; + + + +/** + * @brief Send a position_target message + * + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET; + + i += put_float_by_index(x, i, msg->payload); //x position + i += put_float_by_index(y, i, msg->payload); //y position + i += put_float_by_index(z, i, msg->payload); //z position + i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_position_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_t* position_target) +{ + return mavlink_msg_position_target_pack(system_id, component_id, msg, position_target->x, position_target->y, position_target->z, position_target->yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_target_send(mavlink_channel_t chan, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_position_target_pack(mavlink_system.sysid, mavlink_system.compid, &msg, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POSITION_TARGET UNPACKING + +/** + * @brief Get field x from position_target message + * + * @return x position + */ +static inline float mavlink_msg_position_target_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload)[0]; + r.b[2] = (msg->payload)[1]; + r.b[1] = (msg->payload)[2]; + r.b[0] = (msg->payload)[3]; + return (float)r.f; +} + +/** + * @brief Get field y from position_target message + * + * @return y position + */ +static inline float mavlink_msg_position_target_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from position_target message + * + * @return z position + */ +static inline float mavlink_msg_position_target_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from position_target message + * + * @return yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_target_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_position_target_decode(const mavlink_message_t* msg, mavlink_position_target_t* position_target) +{ + position_target->x = mavlink_msg_position_target_get_x(msg); + position_target->y = mavlink_msg_position_target_get_y(msg); + position_target->z = mavlink_msg_position_target_get_z(msg); + position_target->yaw = mavlink_msg_position_target_get_yaw(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_raw_imu.h b/libraries/mavlink/include/common/mavlink_msg_raw_imu.h new file mode 100644 index 0000000000..ca3567b020 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_raw_imu.h @@ -0,0 +1,221 @@ +// MESSAGE RAW_IMU PACKING + +#define MAVLINK_MSG_ID_RAW_IMU 28 + +typedef struct __mavlink_raw_imu_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch) + int16_t xacc; ///< X acceleration (mg raw) + int16_t yacc; ///< Y acceleration (mg raw) + int16_t zacc; ///< Z acceleration (mg raw) + uint16_t xgyro; ///< Angular speed around X axis (adc units) + uint16_t ygyro; ///< Angular speed around Y axis (adc units) + uint16_t zgyro; ///< Angular speed around Z axis (adc units) + int16_t xmag; ///< X Magnetic field (milli tesla) + int16_t ymag; ///< Y Magnetic field (milli tesla) + int16_t zmag; ///< Z Magnetic field (milli tesla) + +} mavlink_raw_imu_t; + + + +/** + * @brief Send a raw_imu message + * + * @param usec Timestamp (microseconds since UNIX epoch) + * @param xacc X acceleration (mg raw) + * @param yacc Y acceleration (mg raw) + * @param zacc Z acceleration (mg raw) + * @param xgyro Angular speed around X axis (adc units) + * @param ygyro Angular speed around Y axis (adc units) + * @param zgyro Angular speed around Z axis (adc units) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, uint16_t xgyro, uint16_t ygyro, uint16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; + + i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since UNIX epoch) + i += put_int16_t_by_index(xacc, i, msg->payload); //X acceleration (mg raw) + i += put_int16_t_by_index(yacc, i, msg->payload); //Y acceleration (mg raw) + i += put_int16_t_by_index(zacc, i, msg->payload); //Z acceleration (mg raw) + i += put_uint16_t_by_index(xgyro, i, msg->payload); //Angular speed around X axis (adc units) + i += put_uint16_t_by_index(ygyro, i, msg->payload); //Angular speed around Y axis (adc units) + i += put_uint16_t_by_index(zgyro, i, msg->payload); //Angular speed around Z axis (adc units) + i += put_int16_t_by_index(xmag, i, msg->payload); //X Magnetic field (milli tesla) + i += put_int16_t_by_index(ymag, i, msg->payload); //Y Magnetic field (milli tesla) + i += put_int16_t_by_index(zmag, i, msg->payload); //Z Magnetic field (milli tesla) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) +{ + return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, uint16_t xgyro, uint16_t ygyro, uint16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ + mavlink_message_t msg; + mavlink_msg_raw_imu_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RAW_IMU UNPACKING + +/** + * @brief Get field usec from raw_imu message + * + * @return Timestamp (microseconds since UNIX epoch) + */ +static inline uint64_t mavlink_msg_raw_imu_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field xacc from raw_imu message + * + * @return X acceleration (mg raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field yacc from raw_imu message + * + * @return Y acceleration (mg raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field zacc from raw_imu message + * + * @return Z acceleration (mg raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field xgyro from raw_imu message + * + * @return Angular speed around X axis (adc units) + */ +static inline uint16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field ygyro from raw_imu message + * + * @return Angular speed around Y axis (adc units) + */ +static inline uint16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field zgyro from raw_imu message + * + * @return Angular speed around Z axis (adc units) + */ +static inline uint16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field xmag from raw_imu message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field ymag from raw_imu message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field zmag from raw_imu message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu) +{ + raw_imu->usec = mavlink_msg_raw_imu_get_usec(msg); + raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg); + raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg); + raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg); + raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg); + raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg); + raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg); + raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg); + raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); + raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_raw_pressure.h b/libraries/mavlink/include/common/mavlink_msg_raw_pressure.h new file mode 100644 index 0000000000..56c5c06ab7 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_raw_pressure.h @@ -0,0 +1,125 @@ +// MESSAGE RAW_PRESSURE PACKING + +#define MAVLINK_MSG_ID_RAW_PRESSURE 29 + +typedef struct __mavlink_raw_pressure_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch) + int32_t press_abs; ///< Absolute pressure (hectopascal) + int32_t press_diff1; ///< Differential pressure 1 (hectopascal) + int32_t press_diff2; ///< Differential pressure 2 (hectopascal) + +} mavlink_raw_pressure_t; + + + +/** + * @brief Send a raw_pressure message + * + * @param usec Timestamp (microseconds since UNIX epoch) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff1 Differential pressure 1 (hectopascal) + * @param press_diff2 Differential pressure 2 (hectopascal) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int32_t press_abs, int32_t press_diff1, int32_t press_diff2) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; + + i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since UNIX epoch) + i += put_int32_t_by_index(press_abs, i, msg->payload); //Absolute pressure (hectopascal) + i += put_int32_t_by_index(press_diff1, i, msg->payload); //Differential pressure 1 (hectopascal) + i += put_int32_t_by_index(press_diff2, i, msg->payload); //Differential pressure 2 (hectopascal) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) +{ + return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, int32_t press_abs, int32_t press_diff1, int32_t press_diff2) +{ + mavlink_message_t msg; + mavlink_msg_raw_pressure_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, press_abs, press_diff1, press_diff2); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RAW_PRESSURE UNPACKING + +/** + * @brief Get field usec from raw_pressure message + * + * @return Timestamp (microseconds since UNIX epoch) + */ +static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field press_abs from raw_pressure message + * + * @return Absolute pressure (hectopascal) + */ +static inline int32_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field press_diff1 from raw_pressure message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline int32_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field press_diff2 from raw_pressure message + * + * @return Differential pressure 2 (hectopascal) + */ +static inline int32_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int32_t)+sizeof(int32_t))[3]; + return (int32_t)r.i; +} + +static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure) +{ + raw_pressure->usec = mavlink_msg_raw_pressure_get_usec(msg); + raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg); + raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg); + raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_rc_channels_raw.h b/libraries/mavlink/include/common/mavlink_msg_rc_channels_raw.h new file mode 100644 index 0000000000..1853d4a9c1 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_rc_channels_raw.h @@ -0,0 +1,195 @@ +// MESSAGE RC_CHANNELS_RAW PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 + +typedef struct __mavlink_rc_channels_raw_t +{ + uint16_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 + uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% + +} mavlink_rc_channels_raw_t; + + + +/** + * @brief Send a rc_channels_raw message + * + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; + + i += put_uint16_t_by_index(chan1_raw, i, msg->payload); //RC channel 1 value, in microseconds + i += put_uint16_t_by_index(chan2_raw, i, msg->payload); //RC channel 2 value, in microseconds + i += put_uint16_t_by_index(chan3_raw, i, msg->payload); //RC channel 3 value, in microseconds + i += put_uint16_t_by_index(chan4_raw, i, msg->payload); //RC channel 4 value, in microseconds + i += put_uint16_t_by_index(chan5_raw, i, msg->payload); //RC channel 5 value, in microseconds + i += put_uint16_t_by_index(chan6_raw, i, msg->payload); //RC channel 6 value, in microseconds + i += put_uint16_t_by_index(chan7_raw, i, msg->payload); //RC channel 7 value, in microseconds + i += put_uint16_t_by_index(chan8_raw, i, msg->payload); //RC channel 8 value, in microseconds + i += put_uint8_t_by_index(rssi, i, msg->payload); //Receive signal strength indicator, 0: 0%, 255: 100% + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) +{ + return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ + mavlink_message_t msg; + mavlink_msg_rc_channels_raw_pack(mavlink_system.sysid, mavlink_system.compid, &msg, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RC_CHANNELS_RAW UNPACKING + +/** + * @brief Get field chan1_raw from rc_channels_raw message + * + * @return RC channel 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field chan2_raw from rc_channels_raw message + * + * @return RC channel 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field chan3_raw from rc_channels_raw message + * + * @return RC channel 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field chan4_raw from rc_channels_raw message + * + * @return RC channel 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field chan5_raw from rc_channels_raw message + * + * @return RC channel 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field chan6_raw from rc_channels_raw message + * + * @return RC channel 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field chan7_raw from rc_channels_raw message + * + * @return RC channel 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field chan8_raw from rc_channels_raw message + * + * @return RC channel 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field rssi from rc_channels_raw message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; +} + +static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw) +{ + rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg); + rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg); + rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg); + rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg); + rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg); + rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg); + rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg); + rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg); + rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_rc_channels_scaled.h b/libraries/mavlink/include/common/mavlink_msg_rc_channels_scaled.h new file mode 100644 index 0000000000..a6ab314202 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_rc_channels_scaled.h @@ -0,0 +1,195 @@ +// MESSAGE RC_CHANNELS_SCALED PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 36 + +typedef struct __mavlink_rc_channels_scaled_t +{ + int16_t 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 + uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% + +} mavlink_rc_channels_scaled_t; + + + +/** + * @brief Send a rc_channels_scaled message + * + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; + + i += put_int16_t_by_index(chan1_scaled, i, msg->payload); //RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan2_scaled, i, msg->payload); //RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan3_scaled, i, msg->payload); //RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan4_scaled, i, msg->payload); //RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan5_scaled, i, msg->payload); //RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan6_scaled, i, msg->payload); //RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan7_scaled, i, msg->payload); //RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan8_scaled, i, msg->payload); //RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_uint8_t_by_index(rssi, i, msg->payload); //Receive signal strength indicator, 0: 0%, 255: 100% + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ + return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ + mavlink_message_t msg; + mavlink_msg_rc_channels_scaled_pack(mavlink_system.sysid, mavlink_system.compid, &msg, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RC_CHANNELS_SCALED UNPACKING + +/** + * @brief Get field chan1_scaled from rc_channels_scaled message + * + * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan2_scaled from rc_channels_scaled message + * + * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan3_scaled from rc_channels_scaled message + * + * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan4_scaled from rc_channels_scaled message + * + * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan5_scaled from rc_channels_scaled message + * + * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan6_scaled from rc_channels_scaled message + * + * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan7_scaled from rc_channels_scaled message + * + * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan8_scaled from rc_channels_scaled message + * + * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field rssi from rc_channels_scaled message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; +} + +static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ + rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg); + rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg); + rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg); + rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg); + rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg); + rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg); + rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg); + rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg); + rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_request_data_stream.h b/libraries/mavlink/include/common/mavlink_msg_request_data_stream.h new file mode 100644 index 0000000000..6894a73e1c --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_request_data_stream.h @@ -0,0 +1,118 @@ +// MESSAGE REQUEST_DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 + +typedef struct __mavlink_request_data_stream_t +{ + uint8_t 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 + uint16_t req_message_rate; ///< The requested interval between two messages of this type + uint8_t start_stop; ///< 1 to start sending, 0 to stop sending. + +} mavlink_request_data_stream_t; + + + +/** + * @brief Send a request_data_stream message + * + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested message type + * @param req_message_rate The requested interval between two messages of this type + * @param start_stop 1 to start sending, 0 to stop sending. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //The target requested to send the message stream. + i += put_uint8_t_by_index(target_component, i, msg->payload); //The target requested to send the message stream. + i += put_uint8_t_by_index(req_stream_id, i, msg->payload); //The ID of the requested message type + i += put_uint16_t_by_index(req_message_rate, i, msg->payload); //The requested interval between two messages of this type + i += put_uint8_t_by_index(start_stop, i, msg->payload); //1 to start sending, 0 to stop sending. + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) +{ + return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ + mavlink_message_t msg; + mavlink_msg_request_data_stream_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, req_stream_id, req_message_rate, start_stop); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE REQUEST_DATA_STREAM UNPACKING + +/** + * @brief Get field target_system from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field req_stream_id from request_data_stream message + * + * @return The ID of the requested message type + */ +static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field req_message_rate from request_data_stream message + * + * @return The requested interval between two messages of this type + */ +static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field start_stop from request_data_stream message + * + * @return 1 to start sending, 0 to stop sending. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; +} + +static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream) +{ + request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg); + request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg); + request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg); + request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg); + request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_request_dynamic_gyro_calibration.h b/libraries/mavlink/include/common/mavlink_msg_request_dynamic_gyro_calibration.h new file mode 100644 index 0000000000..2893bfdcf3 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_request_dynamic_gyro_calibration.h @@ -0,0 +1,123 @@ +// MESSAGE REQUEST_DYNAMIC_GYRO_CALIBRATION PACKING + +#define MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION 67 + +typedef struct __mavlink_request_dynamic_gyro_calibration_t +{ + uint8_t target_system; ///< The system which should auto-calibrate + uint8_t target_component; ///< The system component which should auto-calibrate + float mode; ///< The current ground-truth rpm + uint8_t axis; ///< The axis to calibrate: 0 roll, 1 pitch, 2 yaw + uint16_t time; ///< The time to average over in ms + +} mavlink_request_dynamic_gyro_calibration_t; + + + +/** + * @brief Send a request_dynamic_gyro_calibration message + * + * @param target_system The system which should auto-calibrate + * @param target_component The system component which should auto-calibrate + * @param mode The current ground-truth rpm + * @param axis The axis to calibrate: 0 roll, 1 pitch, 2 yaw + * @param time The time to average over in ms + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate + i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate + i += put_float_by_index(mode, i, msg->payload); //The current ground-truth rpm + i += put_uint8_t_by_index(axis, i, msg->payload); //The axis to calibrate: 0 roll, 1 pitch, 2 yaw + i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration) +{ + return mavlink_msg_request_dynamic_gyro_calibration_pack(system_id, component_id, msg, request_dynamic_gyro_calibration->target_system, request_dynamic_gyro_calibration->target_component, request_dynamic_gyro_calibration->mode, request_dynamic_gyro_calibration->axis, request_dynamic_gyro_calibration->time); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_dynamic_gyro_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time) +{ + mavlink_message_t msg; + mavlink_msg_request_dynamic_gyro_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, mode, axis, time); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE REQUEST_DYNAMIC_GYRO_CALIBRATION UNPACKING + +/** + * @brief Get field target_system from request_dynamic_gyro_calibration message + * + * @return The system which should auto-calibrate + */ +static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from request_dynamic_gyro_calibration message + * + * @return The system component which should auto-calibrate + */ +static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field mode from request_dynamic_gyro_calibration message + * + * @return The current ground-truth rpm + */ +static inline float mavlink_msg_request_dynamic_gyro_calibration_get_mode(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field axis from request_dynamic_gyro_calibration message + * + * @return The axis to calibrate: 0 roll, 1 pitch, 2 yaw + */ +static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_axis(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; +} + +/** + * @brief Get field time from request_dynamic_gyro_calibration message + * + * @return The time to average over in ms + */ +static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_get_time(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_request_dynamic_gyro_calibration_decode(const mavlink_message_t* msg, mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration) +{ + request_dynamic_gyro_calibration->target_system = mavlink_msg_request_dynamic_gyro_calibration_get_target_system(msg); + request_dynamic_gyro_calibration->target_component = mavlink_msg_request_dynamic_gyro_calibration_get_target_component(msg); + request_dynamic_gyro_calibration->mode = mavlink_msg_request_dynamic_gyro_calibration_get_mode(msg); + request_dynamic_gyro_calibration->axis = mavlink_msg_request_dynamic_gyro_calibration_get_axis(msg); + request_dynamic_gyro_calibration->time = mavlink_msg_request_dynamic_gyro_calibration_get_time(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_request_static_calibration.h b/libraries/mavlink/include/common/mavlink_msg_request_static_calibration.h new file mode 100644 index 0000000000..a7a61e093b --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_request_static_calibration.h @@ -0,0 +1,90 @@ +// MESSAGE REQUEST_STATIC_CALIBRATION PACKING + +#define MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION 68 + +typedef struct __mavlink_request_static_calibration_t +{ + uint8_t target_system; ///< The system which should auto-calibrate + uint8_t target_component; ///< The system component which should auto-calibrate + uint16_t time; ///< The time to average over in ms + +} mavlink_request_static_calibration_t; + + + +/** + * @brief Send a request_static_calibration message + * + * @param target_system The system which should auto-calibrate + * @param target_component The system component which should auto-calibrate + * @param time The time to average over in ms + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_static_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t time) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate + i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate + i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_request_static_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_static_calibration_t* request_static_calibration) +{ + return mavlink_msg_request_static_calibration_pack(system_id, component_id, msg, request_static_calibration->target_system, request_static_calibration->target_component, request_static_calibration->time); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_static_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t time) +{ + mavlink_message_t msg; + mavlink_msg_request_static_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, time); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE REQUEST_STATIC_CALIBRATION UNPACKING + +/** + * @brief Get field target_system from request_static_calibration message + * + * @return The system which should auto-calibrate + */ +static inline uint8_t mavlink_msg_request_static_calibration_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from request_static_calibration message + * + * @return The system component which should auto-calibrate + */ +static inline uint8_t mavlink_msg_request_static_calibration_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field time from request_static_calibration message + * + * @return The time to average over in ms + */ +static inline uint16_t mavlink_msg_request_static_calibration_get_time(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_request_static_calibration_decode(const mavlink_message_t* msg, mavlink_request_static_calibration_t* request_static_calibration) +{ + request_static_calibration->target_system = mavlink_msg_request_static_calibration_get_target_system(msg); + request_static_calibration->target_component = mavlink_msg_request_static_calibration_get_target_component(msg); + request_static_calibration->time = mavlink_msg_request_static_calibration_get_time(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_set_altitude.h b/libraries/mavlink/include/common/mavlink_msg_set_altitude.h new file mode 100644 index 0000000000..b9726f0a8d --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_set_altitude.h @@ -0,0 +1,78 @@ +// MESSAGE SET_ALTITUDE PACKING + +#define MAVLINK_MSG_ID_SET_ALTITUDE 65 + +typedef struct __mavlink_set_altitude_t +{ + uint8_t target; ///< The system setting the altitude + uint32_t mode; ///< The new altitude in meters + +} mavlink_set_altitude_t; + + + +/** + * @brief Send a set_altitude message + * + * @param target The system setting the altitude + * @param mode The new altitude in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint32_t mode) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the altitude + i += put_uint32_t_by_index(mode, i, msg->payload); //The new altitude in meters + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_set_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_altitude_t* set_altitude) +{ + return mavlink_msg_set_altitude_pack(system_id, component_id, msg, set_altitude->target, set_altitude->mode); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_altitude_send(mavlink_channel_t chan, uint8_t target, uint32_t mode) +{ + mavlink_message_t msg; + mavlink_msg_set_altitude_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, mode); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SET_ALTITUDE UNPACKING + +/** + * @brief Get field target from set_altitude message + * + * @return The system setting the altitude + */ +static inline uint8_t mavlink_msg_set_altitude_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field mode from set_altitude message + * + * @return The new altitude in meters + */ +static inline uint32_t mavlink_msg_set_altitude_get_mode(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t))[3]; + return (uint32_t)r.i; +} + +static inline void mavlink_msg_set_altitude_decode(const mavlink_message_t* msg, mavlink_set_altitude_t* set_altitude) +{ + set_altitude->target = mavlink_msg_set_altitude_get_target(msg); + set_altitude->mode = mavlink_msg_set_altitude_get_mode(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_set_mode.h b/libraries/mavlink/include/common/mavlink_msg_set_mode.h new file mode 100644 index 0000000000..ca0a15eb8f --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_set_mode.h @@ -0,0 +1,73 @@ +// MESSAGE SET_MODE PACKING + +#define MAVLINK_MSG_ID_SET_MODE 11 + +typedef struct __mavlink_set_mode_t +{ + uint8_t target; ///< The system setting the mode + uint8_t mode; ///< The new mode + +} mavlink_set_mode_t; + + + +/** + * @brief Send a set_mode message + * + * @param target The system setting the mode + * @param mode The new mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t mode) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_MODE; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the mode + i += put_uint8_t_by_index(mode, i, msg->payload); //The new mode + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) +{ + return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target, set_mode->mode); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t mode) +{ + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, mode); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SET_MODE UNPACKING + +/** + * @brief Get field target from set_mode message + * + * @return The system setting the mode + */ +static inline uint8_t mavlink_msg_set_mode_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field mode from set_mode message + * + * @return The new mode + */ +static inline uint8_t mavlink_msg_set_mode_get_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode) +{ + set_mode->target = mavlink_msg_set_mode_get_target(msg); + set_mode->mode = mavlink_msg_set_mode_get_mode(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_set_nav_mode.h b/libraries/mavlink/include/common/mavlink_msg_set_nav_mode.h new file mode 100644 index 0000000000..4224ac994f --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_set_nav_mode.h @@ -0,0 +1,73 @@ +// MESSAGE SET_NAV_MODE PACKING + +#define MAVLINK_MSG_ID_SET_NAV_MODE 12 + +typedef struct __mavlink_set_nav_mode_t +{ + uint8_t target; ///< The system setting the mode + uint8_t nav_mode; ///< The new navigation mode + +} mavlink_set_nav_mode_t; + + + +/** + * @brief Send a set_nav_mode message + * + * @param target The system setting the mode + * @param nav_mode The new navigation mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_nav_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t nav_mode) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the mode + i += put_uint8_t_by_index(nav_mode, i, msg->payload); //The new navigation mode + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_set_nav_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_nav_mode_t* set_nav_mode) +{ + return mavlink_msg_set_nav_mode_pack(system_id, component_id, msg, set_nav_mode->target, set_nav_mode->nav_mode); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_nav_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t nav_mode) +{ + mavlink_message_t msg; + mavlink_msg_set_nav_mode_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, nav_mode); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SET_NAV_MODE UNPACKING + +/** + * @brief Get field target from set_nav_mode message + * + * @return The system setting the mode + */ +static inline uint8_t mavlink_msg_set_nav_mode_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field nav_mode from set_nav_mode message + * + * @return The new navigation mode + */ +static inline uint8_t mavlink_msg_set_nav_mode_get_nav_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_set_nav_mode_decode(const mavlink_message_t* msg, mavlink_set_nav_mode_t* set_nav_mode) +{ + set_nav_mode->target = mavlink_msg_set_nav_mode_get_target(msg); + set_nav_mode->nav_mode = mavlink_msg_set_nav_mode_get_nav_mode(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_state_correction.h b/libraries/mavlink/include/common/mavlink_msg_state_correction.h new file mode 100644 index 0000000000..94023f67bc --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_state_correction.h @@ -0,0 +1,216 @@ +// MESSAGE STATE_CORRECTION PACKING + +#define MAVLINK_MSG_ID_STATE_CORRECTION 64 + +typedef struct __mavlink_state_correction_t +{ + float 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 + +} mavlink_state_correction_t; + + + +/** + * @brief Send a state_correction message + * + * @param xErr x position error + * @param yErr y position error + * @param zErr z position error + * @param rollErr roll error (radians) + * @param pitchErr pitch error (radians) + * @param yawErr yaw error (radians) + * @param vxErr x velocity + * @param vyErr y velocity + * @param vzErr z velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; + + i += put_float_by_index(xErr, i, msg->payload); //x position error + i += put_float_by_index(yErr, i, msg->payload); //y position error + i += put_float_by_index(zErr, i, msg->payload); //z position error + i += put_float_by_index(rollErr, i, msg->payload); //roll error (radians) + i += put_float_by_index(pitchErr, i, msg->payload); //pitch error (radians) + i += put_float_by_index(yawErr, i, msg->payload); //yaw error (radians) + i += put_float_by_index(vxErr, i, msg->payload); //x velocity + i += put_float_by_index(vyErr, i, msg->payload); //y velocity + i += put_float_by_index(vzErr, i, msg->payload); //z velocity + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction) +{ + return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) +{ + mavlink_message_t msg; + mavlink_msg_state_correction_pack(mavlink_system.sysid, mavlink_system.compid, &msg, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE STATE_CORRECTION UNPACKING + +/** + * @brief Get field xErr from state_correction message + * + * @return x position error + */ +static inline float mavlink_msg_state_correction_get_xErr(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload)[0]; + r.b[2] = (msg->payload)[1]; + r.b[1] = (msg->payload)[2]; + r.b[0] = (msg->payload)[3]; + return (float)r.f; +} + +/** + * @brief Get field yErr from state_correction message + * + * @return y position error + */ +static inline float mavlink_msg_state_correction_get_yErr(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field zErr from state_correction message + * + * @return z position error + */ +static inline float mavlink_msg_state_correction_get_zErr(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field rollErr from state_correction message + * + * @return roll error (radians) + */ +static inline float mavlink_msg_state_correction_get_rollErr(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitchErr from state_correction message + * + * @return pitch error (radians) + */ +static inline float mavlink_msg_state_correction_get_pitchErr(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yawErr from state_correction message + * + * @return yaw error (radians) + */ +static inline float mavlink_msg_state_correction_get_yawErr(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vxErr from state_correction message + * + * @return x velocity + */ +static inline float mavlink_msg_state_correction_get_vxErr(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vyErr from state_correction message + * + * @return y velocity + */ +static inline float mavlink_msg_state_correction_get_vyErr(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vzErr from state_correction message + * + * @return z velocity + */ +static inline float mavlink_msg_state_correction_get_vzErr(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* msg, mavlink_state_correction_t* state_correction) +{ + state_correction->xErr = mavlink_msg_state_correction_get_xErr(msg); + state_correction->yErr = mavlink_msg_state_correction_get_yErr(msg); + state_correction->zErr = mavlink_msg_state_correction_get_zErr(msg); + state_correction->rollErr = mavlink_msg_state_correction_get_rollErr(msg); + state_correction->pitchErr = mavlink_msg_state_correction_get_pitchErr(msg); + state_correction->yawErr = mavlink_msg_state_correction_get_yawErr(msg); + state_correction->vxErr = mavlink_msg_state_correction_get_vxErr(msg); + state_correction->vyErr = mavlink_msg_state_correction_get_vyErr(msg); + state_correction->vzErr = mavlink_msg_state_correction_get_vzErr(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_statustext.h b/libraries/mavlink/include/common/mavlink_msg_statustext.h new file mode 100644 index 0000000000..6470e112d4 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_statustext.h @@ -0,0 +1,76 @@ +// MESSAGE STATUSTEXT PACKING + +#define MAVLINK_MSG_ID_STATUSTEXT 254 + +typedef struct __mavlink_statustext_t +{ + uint8_t severity; ///< Severity of status, 0 = info message, 255 = critical fault + int8_t text[50]; ///< Status text message, without null termination character + +} mavlink_statustext_t; + +#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 + + +/** + * @brief Send a statustext message + * + * @param severity Severity of status, 0 = info message, 255 = critical fault + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t severity, const int8_t* text) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; + + i += put_uint8_t_by_index(severity, i, msg->payload); //Severity of status, 0 = info message, 255 = critical fault + i += put_array_by_index(text, 50, i, msg->payload); //Status text message, without null termination character + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext) +{ + return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const int8_t* text) +{ + mavlink_message_t msg; + mavlink_msg_statustext_pack(mavlink_system.sysid, mavlink_system.compid, &msg, severity, text); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE STATUSTEXT UNPACKING + +/** + * @brief Get field severity from statustext message + * + * @return Severity of status, 0 = info message, 255 = critical fault + */ +static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field text from statustext message + * + * @return Status text message, without null termination character + */ +static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t), 50); + return 50; +} + +static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext) +{ + statustext->severity = mavlink_msg_statustext_get_severity(msg); + mavlink_msg_statustext_get_text(msg, statustext->text); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_sys_status.h b/libraries/mavlink/include/common/mavlink_msg_sys_status.h new file mode 100644 index 0000000000..54971fec66 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_sys_status.h @@ -0,0 +1,152 @@ +// MESSAGE SYS_STATUS PACKING + +#define MAVLINK_MSG_ID_SYS_STATUS 34 + +typedef struct __mavlink_sys_status_t +{ + uint8_t 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 + uint16_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) + uint8_t motor_block; ///< Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off) + uint16_t packet_drop; ///< Dropped packets (packets that were corrupted on reception on the MAV) + +} mavlink_sys_status_t; + + + +/** + * @brief Send a sys_status message + * + * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM + * @param status System status flag, see MAV_STATUS ENUM + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param vbat Battery voltage, in millivolts (1 = 1 millivolt) + * @param motor_block Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off) + * @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint8_t motor_block, uint16_t packet_drop) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; + + i += put_uint8_t_by_index(mode, i, msg->payload); //System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + i += put_uint8_t_by_index(nav_mode, i, msg->payload); //Navigation mode, see MAV_NAV_MODE ENUM + i += put_uint8_t_by_index(status, i, msg->payload); //System status flag, see MAV_STATUS ENUM + i += put_uint16_t_by_index(load, i, msg->payload); //Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + i += put_uint16_t_by_index(vbat, i, msg->payload); //Battery voltage, in millivolts (1 = 1 millivolt) + i += put_uint8_t_by_index(motor_block, i, msg->payload); //Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off) + i += put_uint16_t_by_index(packet_drop, i, msg->payload); //Dropped packets (packets that were corrupted on reception on the MAV) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) +{ + return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->mode, sys_status->nav_mode, sys_status->status, sys_status->load, sys_status->vbat, sys_status->motor_block, sys_status->packet_drop); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint8_t motor_block, uint16_t packet_drop) +{ + mavlink_message_t msg; + mavlink_msg_sys_status_pack(mavlink_system.sysid, mavlink_system.compid, &msg, mode, nav_mode, status, load, vbat, motor_block, packet_drop); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SYS_STATUS UNPACKING + +/** + * @brief Get field mode from sys_status message + * + * @return System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + */ +static inline uint8_t mavlink_msg_sys_status_get_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field nav_mode from sys_status message + * + * @return Navigation mode, see MAV_NAV_MODE ENUM + */ +static inline uint8_t mavlink_msg_sys_status_get_nav_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field status from sys_status message + * + * @return System status flag, see MAV_STATUS ENUM + */ +static inline uint8_t mavlink_msg_sys_status_get_status(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field load from sys_status message + * + * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + */ +static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field vbat from sys_status message + * + * @return Battery voltage, in millivolts (1 = 1 millivolt) + */ +static inline uint16_t mavlink_msg_sys_status_get_vbat(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field motor_block from sys_status message + * + * @return Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off) + */ +static inline uint8_t mavlink_msg_sys_status_get_motor_block(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; +} + +/** + * @brief Get field packet_drop from sys_status message + * + * @return Dropped packets (packets that were corrupted on reception on the MAV) + */ +static inline uint16_t mavlink_msg_sys_status_get_packet_drop(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status) +{ + sys_status->mode = mavlink_msg_sys_status_get_mode(msg); + sys_status->nav_mode = mavlink_msg_sys_status_get_nav_mode(msg); + sys_status->status = mavlink_msg_sys_status_get_status(msg); + sys_status->load = mavlink_msg_sys_status_get_load(msg); + sys_status->vbat = mavlink_msg_sys_status_get_vbat(msg); + sys_status->motor_block = mavlink_msg_sys_status_get_motor_block(msg); + sys_status->packet_drop = mavlink_msg_sys_status_get_packet_drop(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_system_time.h b/libraries/mavlink/include/common/mavlink_msg_system_time.h new file mode 100644 index 0000000000..0aafc03949 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_system_time.h @@ -0,0 +1,68 @@ +// MESSAGE SYSTEM_TIME PACKING + +#define MAVLINK_MSG_ID_SYSTEM_TIME 2 + +typedef struct __mavlink_system_time_t +{ + uint64_t time_usec; ///< Timestamp of the master clock in microseconds since UNIX epoch. + +} mavlink_system_time_t; + + + +/** + * @brief Send a system_time message + * + * @param time_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t time_usec) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; + + i += put_uint64_t_by_index(time_usec, i, msg->payload); //Timestamp of the master clock in microseconds since UNIX epoch. + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time) +{ + return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_usec); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_usec) +{ + mavlink_message_t msg; + mavlink_msg_system_time_pack(mavlink_system.sysid, mavlink_system.compid, &msg, time_usec); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SYSTEM_TIME UNPACKING + +/** + * @brief Get field time_usec from system_time message + * + * @return Timestamp of the master clock in microseconds since UNIX epoch. + */ +static inline uint64_t mavlink_msg_system_time_get_time_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time) +{ + system_time->time_usec = mavlink_msg_system_time_get_time_usec(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_waypoint.h b/libraries/mavlink/include/common/mavlink_msg_waypoint.h new file mode 100644 index 0000000000..9d955a857e --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_waypoint.h @@ -0,0 +1,293 @@ +// MESSAGE WAYPOINT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT 39 + +typedef struct __mavlink_waypoint_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint16_t seq; ///< Sequence + uint8_t frame; ///< The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + uint8_t action; ///< The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h + float orbit; ///< Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint + uint8_t orbit_direction; ///< Direction of the orbit circling: 0: clockwise, 1: counter-clockwise + float param1; ///< For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters + float param2; ///< For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds + uint8_t current; ///< false:0, true:1 + float x; ///< local: x position, global: longitude + float y; ///< y position: global: latitude + float z; ///< z position: global: altitude + float yaw; ///< yaw orientation in radians, 0 = NORTH + uint8_t autocontinue; ///< autocontinue to next wp + +} mavlink_waypoint_t; + + + +/** + * @brief Send a waypoint message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + * @param action The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h + * @param orbit Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint + * @param orbit_direction Direction of the orbit circling: 0: clockwise, 1: counter-clockwise + * @param param1 For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters + * @param param2 For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds + * @param current false:0, true:1 + * @param x local: x position, global: longitude + * @param y y position: global: latitude + * @param z z position: global: altitude + * @param yaw yaw orientation in radians, 0 = NORTH + * @param autocontinue autocontinue to next wp + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t action, float orbit, uint8_t orbit_direction, float param1, float param2, uint8_t current, float x, float y, float z, float yaw, uint8_t autocontinue) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence + i += put_uint8_t_by_index(frame, i, msg->payload); //The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + i += put_uint8_t_by_index(action, i, msg->payload); //The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h + i += put_float_by_index(orbit, i, msg->payload); //Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint + i += put_uint8_t_by_index(orbit_direction, i, msg->payload); //Direction of the orbit circling: 0: clockwise, 1: counter-clockwise + i += put_float_by_index(param1, i, msg->payload); //For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters + i += put_float_by_index(param2, i, msg->payload); //For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds + i += put_uint8_t_by_index(current, i, msg->payload); //false:0, true:1 + i += put_float_by_index(x, i, msg->payload); //local: x position, global: longitude + i += put_float_by_index(y, i, msg->payload); //y position: global: latitude + i += put_float_by_index(z, i, msg->payload); //z position: global: altitude + i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH + i += put_uint8_t_by_index(autocontinue, i, msg->payload); //autocontinue to next wp + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_t* waypoint) +{ + return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->action, waypoint->orbit, waypoint->orbit_direction, waypoint->param1, waypoint->param2, waypoint->current, waypoint->x, waypoint->y, waypoint->z, waypoint->yaw, waypoint->autocontinue); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t action, float orbit, uint8_t orbit_direction, float param1, float param2, uint8_t current, float x, float y, float z, float yaw, uint8_t autocontinue) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, seq, frame, action, orbit, orbit_direction, param1, param2, current, x, y, z, yaw, autocontinue); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT UNPACKING + +/** + * @brief Get field target_system from waypoint message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field seq from waypoint message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_get_seq(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field frame from waypoint message + * + * @return The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_waypoint_get_frame(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; +} + +/** + * @brief Get field action from waypoint message + * + * @return The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h + */ +static inline uint8_t mavlink_msg_waypoint_get_action(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field orbit from waypoint message + * + * @return Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint + */ +static inline float mavlink_msg_waypoint_get_orbit(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field orbit_direction from waypoint message + * + * @return Direction of the orbit circling: 0: clockwise, 1: counter-clockwise + */ +static inline uint8_t mavlink_msg_waypoint_get_orbit_direction(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; +} + +/** + * @brief Get field param1 from waypoint message + * + * @return For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters + */ +static inline float mavlink_msg_waypoint_get_param1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field param2 from waypoint message + * + * @return For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds + */ +static inline float mavlink_msg_waypoint_get_param2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field current from waypoint message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_waypoint_get_current(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; +} + +/** + * @brief Get field x from waypoint message + * + * @return local: x position, global: longitude + */ +static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from waypoint message + * + * @return y position: global: latitude + */ +static inline float mavlink_msg_waypoint_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from waypoint message + * + * @return z position: global: altitude + */ +static inline float mavlink_msg_waypoint_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from waypoint message + * + * @return yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_waypoint_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field autocontinue from waypoint message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_waypoint_get_autocontinue(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; +} + +static inline void mavlink_msg_waypoint_decode(const mavlink_message_t* msg, mavlink_waypoint_t* waypoint) +{ + waypoint->target_system = mavlink_msg_waypoint_get_target_system(msg); + waypoint->target_component = mavlink_msg_waypoint_get_target_component(msg); + waypoint->seq = mavlink_msg_waypoint_get_seq(msg); + waypoint->frame = mavlink_msg_waypoint_get_frame(msg); + waypoint->action = mavlink_msg_waypoint_get_action(msg); + waypoint->orbit = mavlink_msg_waypoint_get_orbit(msg); + waypoint->orbit_direction = mavlink_msg_waypoint_get_orbit_direction(msg); + waypoint->param1 = mavlink_msg_waypoint_get_param1(msg); + waypoint->param2 = mavlink_msg_waypoint_get_param2(msg); + waypoint->current = mavlink_msg_waypoint_get_current(msg); + waypoint->x = mavlink_msg_waypoint_get_x(msg); + waypoint->y = mavlink_msg_waypoint_get_y(msg); + waypoint->z = mavlink_msg_waypoint_get_z(msg); + waypoint->yaw = mavlink_msg_waypoint_get_yaw(msg); + waypoint->autocontinue = mavlink_msg_waypoint_get_autocontinue(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_waypoint_ack.h b/libraries/mavlink/include/common/mavlink_msg_waypoint_ack.h new file mode 100644 index 0000000000..ffbb684780 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_waypoint_ack.h @@ -0,0 +1,87 @@ +// MESSAGE WAYPOINT_ACK PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_ACK 47 + +typedef struct __mavlink_waypoint_ack_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t type; ///< 0: OK, 1: Error + +} mavlink_waypoint_ack_t; + + + +/** + * @brief Send a waypoint_ack message + * + * @param target_system System ID + * @param target_component Component ID + * @param type 0: OK, 1: Error + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t type) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_uint8_t_by_index(type, i, msg->payload); //0: OK, 1: Error + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_waypoint_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_ack_t* waypoint_ack) +{ + return mavlink_msg_waypoint_ack_pack(system_id, component_id, msg, waypoint_ack->target_system, waypoint_ack->target_component, waypoint_ack->type); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_ack_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, type); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_ACK UNPACKING + +/** + * @brief Get field target_system from waypoint_ack message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_ack_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_ack message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_ack_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field type from waypoint_ack message + * + * @return 0: OK, 1: Error + */ +static inline uint8_t mavlink_msg_waypoint_ack_get_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_waypoint_ack_decode(const mavlink_message_t* msg, mavlink_waypoint_ack_t* waypoint_ack) +{ + waypoint_ack->target_system = mavlink_msg_waypoint_ack_get_target_system(msg); + waypoint_ack->target_component = mavlink_msg_waypoint_ack_get_target_component(msg); + waypoint_ack->type = mavlink_msg_waypoint_ack_get_type(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_waypoint_clear_all.h b/libraries/mavlink/include/common/mavlink_msg_waypoint_clear_all.h new file mode 100644 index 0000000000..ee479f8ec4 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_waypoint_clear_all.h @@ -0,0 +1,73 @@ +// MESSAGE WAYPOINT_CLEAR_ALL PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL 45 + +typedef struct __mavlink_waypoint_clear_all_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + +} mavlink_waypoint_clear_all_t; + + + +/** + * @brief Send a waypoint_clear_all message + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_waypoint_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_clear_all_t* waypoint_clear_all) +{ + return mavlink_msg_waypoint_clear_all_pack(system_id, component_id, msg, waypoint_clear_all->target_system, waypoint_clear_all->target_component); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_clear_all_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_CLEAR_ALL UNPACKING + +/** + * @brief Get field target_system from waypoint_clear_all message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_clear_all message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_waypoint_clear_all_decode(const mavlink_message_t* msg, mavlink_waypoint_clear_all_t* waypoint_clear_all) +{ + waypoint_clear_all->target_system = mavlink_msg_waypoint_clear_all_get_target_system(msg); + waypoint_clear_all->target_component = mavlink_msg_waypoint_clear_all_get_target_component(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_waypoint_count.h b/libraries/mavlink/include/common/mavlink_msg_waypoint_count.h new file mode 100644 index 0000000000..dee76afa87 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_waypoint_count.h @@ -0,0 +1,90 @@ +// MESSAGE WAYPOINT_COUNT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_COUNT 44 + +typedef struct __mavlink_waypoint_count_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint16_t count; ///< Number of Waypoints in the Sequence + +} mavlink_waypoint_count_t; + + + +/** + * @brief Send a waypoint_count message + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of Waypoints in the Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t count) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_uint16_t_by_index(count, i, msg->payload); //Number of Waypoints in the Sequence + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_waypoint_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_count_t* waypoint_count) +{ + return mavlink_msg_waypoint_count_pack(system_id, component_id, msg, waypoint_count->target_system, waypoint_count->target_component, waypoint_count->count); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_count_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, count); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_COUNT UNPACKING + +/** + * @brief Get field target_system from waypoint_count message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_count_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_count message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_count_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field count from waypoint_count message + * + * @return Number of Waypoints in the Sequence + */ +static inline uint16_t mavlink_msg_waypoint_count_get_count(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_waypoint_count_decode(const mavlink_message_t* msg, mavlink_waypoint_count_t* waypoint_count) +{ + waypoint_count->target_system = mavlink_msg_waypoint_count_get_target_system(msg); + waypoint_count->target_component = mavlink_msg_waypoint_count_get_target_component(msg); + waypoint_count->count = mavlink_msg_waypoint_count_get_count(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_waypoint_current.h b/libraries/mavlink/include/common/mavlink_msg_waypoint_current.h new file mode 100644 index 0000000000..d1c8308227 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_waypoint_current.h @@ -0,0 +1,62 @@ +// MESSAGE WAYPOINT_CURRENT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_CURRENT 42 + +typedef struct __mavlink_waypoint_current_t +{ + uint16_t seq; ///< Sequence + +} mavlink_waypoint_current_t; + + + +/** + * @brief Send a waypoint_current message + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT; + + i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_waypoint_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_current_t* waypoint_current) +{ + return mavlink_msg_waypoint_current_pack(system_id, component_id, msg, waypoint_current->seq); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_current_send(mavlink_channel_t chan, uint16_t seq) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_current_pack(mavlink_system.sysid, mavlink_system.compid, &msg, seq); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_CURRENT UNPACKING + +/** + * @brief Get field seq from waypoint_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_current_get_seq(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_waypoint_current_decode(const mavlink_message_t* msg, mavlink_waypoint_current_t* waypoint_current) +{ + waypoint_current->seq = mavlink_msg_waypoint_current_get_seq(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_waypoint_reached.h b/libraries/mavlink/include/common/mavlink_msg_waypoint_reached.h new file mode 100644 index 0000000000..6ecfc495bd --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_waypoint_reached.h @@ -0,0 +1,62 @@ +// MESSAGE WAYPOINT_REACHED PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_REACHED 46 + +typedef struct __mavlink_waypoint_reached_t +{ + uint16_t seq; ///< Sequence + +} mavlink_waypoint_reached_t; + + + +/** + * @brief Send a waypoint_reached message + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED; + + i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_waypoint_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_reached_t* waypoint_reached) +{ + return mavlink_msg_waypoint_reached_pack(system_id, component_id, msg, waypoint_reached->seq); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_reached_send(mavlink_channel_t chan, uint16_t seq) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_reached_pack(mavlink_system.sysid, mavlink_system.compid, &msg, seq); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_REACHED UNPACKING + +/** + * @brief Get field seq from waypoint_reached message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_reached_get_seq(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_waypoint_reached_decode(const mavlink_message_t* msg, mavlink_waypoint_reached_t* waypoint_reached) +{ + waypoint_reached->seq = mavlink_msg_waypoint_reached_get_seq(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_waypoint_request.h b/libraries/mavlink/include/common/mavlink_msg_waypoint_request.h new file mode 100644 index 0000000000..2e560d2f82 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_waypoint_request.h @@ -0,0 +1,90 @@ +// MESSAGE WAYPOINT_REQUEST PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST 40 + +typedef struct __mavlink_waypoint_request_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint16_t seq; ///< Sequence + +} mavlink_waypoint_request_t; + + + +/** + * @brief Send a waypoint_request message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_waypoint_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_t* waypoint_request) +{ + return mavlink_msg_waypoint_request_pack(system_id, component_id, msg, waypoint_request->target_system, waypoint_request->target_component, waypoint_request->seq); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_request_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, seq); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_REQUEST UNPACKING + +/** + * @brief Get field target_system from waypoint_request message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_request_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_request message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_request_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field seq from waypoint_request message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_request_get_seq(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_waypoint_request_decode(const mavlink_message_t* msg, mavlink_waypoint_request_t* waypoint_request) +{ + waypoint_request->target_system = mavlink_msg_waypoint_request_get_target_system(msg); + waypoint_request->target_component = mavlink_msg_waypoint_request_get_target_component(msg); + waypoint_request->seq = mavlink_msg_waypoint_request_get_seq(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_waypoint_request_list.h b/libraries/mavlink/include/common/mavlink_msg_waypoint_request_list.h new file mode 100644 index 0000000000..0e52cb966f --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_waypoint_request_list.h @@ -0,0 +1,73 @@ +// MESSAGE WAYPOINT_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST 43 + +typedef struct __mavlink_waypoint_request_list_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + +} mavlink_waypoint_request_list_t; + + + +/** + * @brief Send a waypoint_request_list message + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_waypoint_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_list_t* waypoint_request_list) +{ + return mavlink_msg_waypoint_request_list_pack(system_id, component_id, msg, waypoint_request_list->target_system, waypoint_request_list->target_component); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_request_list_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_REQUEST_LIST UNPACKING + +/** + * @brief Get field target_system from waypoint_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_request_list_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_request_list_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_waypoint_request_list_decode(const mavlink_message_t* msg, mavlink_waypoint_request_list_t* waypoint_request_list) +{ + waypoint_request_list->target_system = mavlink_msg_waypoint_request_list_get_target_system(msg); + waypoint_request_list->target_component = mavlink_msg_waypoint_request_list_get_target_component(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_waypoint_set_current.h b/libraries/mavlink/include/common/mavlink_msg_waypoint_set_current.h new file mode 100644 index 0000000000..c2a468d5d8 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_waypoint_set_current.h @@ -0,0 +1,90 @@ +// MESSAGE WAYPOINT_SET_CURRENT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT 41 + +typedef struct __mavlink_waypoint_set_current_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint16_t seq; ///< Sequence + +} mavlink_waypoint_set_current_t; + + + +/** + * @brief Send a waypoint_set_current message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_waypoint_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_set_current_t* waypoint_set_current) +{ + return mavlink_msg_waypoint_set_current_pack(system_id, component_id, msg, waypoint_set_current->target_system, waypoint_set_current->target_component, waypoint_set_current->seq); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_set_current_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, seq); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_SET_CURRENT UNPACKING + +/** + * @brief Get field target_system from waypoint_set_current message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_set_current_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_set_current message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_set_current_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field seq from waypoint_set_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_set_current_get_seq(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_waypoint_set_current_decode(const mavlink_message_t* msg, mavlink_waypoint_set_current_t* waypoint_set_current) +{ + waypoint_set_current->target_system = mavlink_msg_waypoint_set_current_get_target_system(msg); + waypoint_set_current->target_component = mavlink_msg_waypoint_set_current_get_target_component(msg); + waypoint_set_current->seq = mavlink_msg_waypoint_set_current_get_seq(msg); +} diff --git a/libraries/mavlink/include/common/mavlink_msg_waypoint_set_global_reference.h b/libraries/mavlink/include/common/mavlink_msg_waypoint_set_global_reference.h new file mode 100644 index 0000000000..5dbb5573f8 --- /dev/null +++ b/libraries/mavlink/include/common/mavlink_msg_waypoint_set_global_reference.h @@ -0,0 +1,225 @@ +// MESSAGE WAYPOINT_SET_GLOBAL_REFERENCE PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_SET_GLOBAL_REFERENCE 48 + +typedef struct __mavlink_waypoint_set_global_reference_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + float global_x; ///< global x position + float global_y; ///< global y position + float global_z; ///< global z position + float global_yaw; ///< global yaw orientation in radians, 0 = NORTH + float local_x; ///< local x position that matches the global x position + float local_y; ///< local y position that matches the global y position + float local_z; ///< local z position that matches the global z position + float local_yaw; ///< local yaw that matches the global yaw orientation + +} mavlink_waypoint_set_global_reference_t; + + + +/** + * @brief Send a waypoint_set_global_reference message + * + * @param target_system System ID + * @param target_component Component ID + * @param global_x global x position + * @param global_y global y position + * @param global_z global z position + * @param global_yaw global yaw orientation in radians, 0 = NORTH + * @param local_x local x position that matches the global x position + * @param local_y local y position that matches the global y position + * @param local_z local z position that matches the global z position + * @param local_yaw local yaw that matches the global yaw orientation + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_set_global_reference_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float global_x, float global_y, float global_z, float global_yaw, float local_x, float local_y, float local_z, float local_yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_GLOBAL_REFERENCE; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_float_by_index(global_x, i, msg->payload); //global x position + i += put_float_by_index(global_y, i, msg->payload); //global y position + i += put_float_by_index(global_z, i, msg->payload); //global z position + i += put_float_by_index(global_yaw, i, msg->payload); //global yaw orientation in radians, 0 = NORTH + i += put_float_by_index(local_x, i, msg->payload); //local x position that matches the global x position + i += put_float_by_index(local_y, i, msg->payload); //local y position that matches the global y position + i += put_float_by_index(local_z, i, msg->payload); //local z position that matches the global z position + i += put_float_by_index(local_yaw, i, msg->payload); //local yaw that matches the global yaw orientation + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_waypoint_set_global_reference_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_set_global_reference_t* waypoint_set_global_reference) +{ + return mavlink_msg_waypoint_set_global_reference_pack(system_id, component_id, msg, waypoint_set_global_reference->target_system, waypoint_set_global_reference->target_component, waypoint_set_global_reference->global_x, waypoint_set_global_reference->global_y, waypoint_set_global_reference->global_z, waypoint_set_global_reference->global_yaw, waypoint_set_global_reference->local_x, waypoint_set_global_reference->local_y, waypoint_set_global_reference->local_z, waypoint_set_global_reference->local_yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_set_global_reference_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float global_x, float global_y, float global_z, float global_yaw, float local_x, float local_y, float local_z, float local_yaw) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_set_global_reference_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, global_x, global_y, global_z, global_yaw, local_x, local_y, local_z, local_yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_SET_GLOBAL_REFERENCE UNPACKING + +/** + * @brief Get field target_system from waypoint_set_global_reference message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_set_global_reference_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_set_global_reference message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_set_global_reference_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field global_x from waypoint_set_global_reference message + * + * @return global x position + */ +static inline float mavlink_msg_waypoint_set_global_reference_get_global_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field global_y from waypoint_set_global_reference message + * + * @return global y position + */ +static inline float mavlink_msg_waypoint_set_global_reference_get_global_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field global_z from waypoint_set_global_reference message + * + * @return global z position + */ +static inline float mavlink_msg_waypoint_set_global_reference_get_global_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field global_yaw from waypoint_set_global_reference message + * + * @return global yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_waypoint_set_global_reference_get_global_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field local_x from waypoint_set_global_reference message + * + * @return local x position that matches the global x position + */ +static inline float mavlink_msg_waypoint_set_global_reference_get_local_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field local_y from waypoint_set_global_reference message + * + * @return local y position that matches the global y position + */ +static inline float mavlink_msg_waypoint_set_global_reference_get_local_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field local_z from waypoint_set_global_reference message + * + * @return local z position that matches the global z position + */ +static inline float mavlink_msg_waypoint_set_global_reference_get_local_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field local_yaw from waypoint_set_global_reference message + * + * @return local yaw that matches the global yaw orientation + */ +static inline float mavlink_msg_waypoint_set_global_reference_get_local_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_waypoint_set_global_reference_decode(const mavlink_message_t* msg, mavlink_waypoint_set_global_reference_t* waypoint_set_global_reference) +{ + waypoint_set_global_reference->target_system = mavlink_msg_waypoint_set_global_reference_get_target_system(msg); + waypoint_set_global_reference->target_component = mavlink_msg_waypoint_set_global_reference_get_target_component(msg); + waypoint_set_global_reference->global_x = mavlink_msg_waypoint_set_global_reference_get_global_x(msg); + waypoint_set_global_reference->global_y = mavlink_msg_waypoint_set_global_reference_get_global_y(msg); + waypoint_set_global_reference->global_z = mavlink_msg_waypoint_set_global_reference_get_global_z(msg); + waypoint_set_global_reference->global_yaw = mavlink_msg_waypoint_set_global_reference_get_global_yaw(msg); + waypoint_set_global_reference->local_x = mavlink_msg_waypoint_set_global_reference_get_local_x(msg); + waypoint_set_global_reference->local_y = mavlink_msg_waypoint_set_global_reference_get_local_y(msg); + waypoint_set_global_reference->local_z = mavlink_msg_waypoint_set_global_reference_get_local_z(msg); + waypoint_set_global_reference->local_yaw = mavlink_msg_waypoint_set_global_reference_get_local_yaw(msg); +} diff --git a/libraries/mavlink/include/documentation.dox b/libraries/mavlink/include/documentation.dox new file mode 100644 index 0000000000..49de0050e4 --- /dev/null +++ b/libraries/mavlink/include/documentation.dox @@ -0,0 +1,41 @@ +/** + * @file + * @brief MAVLink communication protocol + * + * @author Lorenz Meier + * + */ + + +/** + * @mainpage MAVLink API Documentation + * + * @section intro_sec Introduction + * + * This API documentation covers the MAVLink + * protocol developed PIXHAWK project. + * In case you have generated this documentation locally, the most recent version (generated on every commit) + * is also publicly available on the internet. + * + * @sa http://pixhawk.ethz.ch/api/qgroundcontrol/ - Groundstation code base + * @sa http://pixhawk.ethz.ch/api/mavlink - (this) MAVLink communication protocol + * @sa http://pixhawk.ethz.ch/api/imu_autopilot/ - Flight board (ARM MCU) code base + * @sa http://pixhawk.ethz.ch/api/ai_vision - Computer Vision / AI API docs + * + * @section further_sec Further Information + * + * How to run our software and a general overview of the software architecture is documented in the project + * wiki pages. + * + * @sa http://pixhawk.ethz.ch/software/mavlink/ - MAVLink main documentation + * + * See the PIXHAWK website for more information. + * + * @section usage_sec Doxygen Usage + * + * You can exclude files from being parsed into this Doxygen documentation + * by adding them to the EXCLUDE list in the file in embedded/cmake/doc/api/doxy.config.in. + * + * + * + **/ diff --git a/libraries/mavlink/include/mavlink_types.h b/libraries/mavlink/include/mavlink_types.h new file mode 100644 index 0000000000..53e7f5f75e --- /dev/null +++ b/libraries/mavlink/include/mavlink_types.h @@ -0,0 +1,197 @@ +#ifndef MAVLINK_TYPES_H_ +#define MAVLINK_TYPES_H_ + +#include "inttypes.h" + +enum MAV_CLASS { + MAV_CLASS_GENERIC = 0, + MAV_CLASS_PIXHAWK = 1, + MAV_CLASS_SLUGS = 2, + MAV_CLASS_ARDUPILOTMEGA = 3 +}; + +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_NB ///< Number of MAV actions +}; + +enum MAV_MODE +{ + MAV_MODE_UNINIT = 0, + 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_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 +}; + +enum MAV_TYPE +{ + MAV_GENERIC = 0, + MAV_FIXED_WING = 1, + MAV_QUADROTOR = 2, + MAV_COAXIAL = 3, + MAV_HELICOPTER = 4, + MAV_GROUND = 5, + OCU = 6 +}; + +enum MAV_AUTOPILOT_TYPE +{ + MAV_AUTOPILOT_GENERIC = 0, + MAV_AUTOPILOT_PIXHAWK = 1, + MAV_AUTOPILOT_SLUGS = 2, + MAV_AUTOPILOT_ARDUPILOTMEGA = 3 +}; + +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_IMU = 200 +}; + +enum MAV_FRAME +{ + MAV_FRAME_GLOBAL = 0, + MAV_FRAME_LOCAL = 1 +}; + +enum MAV_DATA_STREAM{ + MAV_DATA_STREAM_ALL = 0, + MAV_DATA_STREAM_RAW_SENSORS = 1, + MAV_DATA_STREAM_EXTENDED_STATUS = 2, + MAV_DATA_STREAM_RC_CHANNELS = 3, + MAV_DATA_STREAM_RAW_CONTROLLER = 4, + MAV_DATA_STREAM_RAW_SENSOR_FUSION = 5, + MAV_DATA_STREAM_POSITION = 6, + MAV_DATA_STREAM_EXTRA1 = 7, + MAV_DATA_STREAM_EXTRA2 = 8, + MAV_DATA_STREAM_EXTRA3 = 9 +}; + + + +#define MAVLINK_STX 0x55 ///< Packet start sign +#define MAVLINK_STX_LEN 1 ///< Length of start sign +#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length + +#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 + MAVLINK_STX_LEN) ///< 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_NUM_NON_STX_PAYLOAD_BYTES (MAVLINK_NUM_NON_PAYLOAD_BYTES - MAVLINK_STX_LEN) + +#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length +//#define MAVLINK_MAX_DATA_LEN MAVLINK_MAX_PACKET_LEN - MAVLINK_STX_LEN + +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 +} mavlink_system_t; + +typedef struct __mavlink_message { + 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 + uint8_t payload[MAVLINK_MAX_PAYLOAD_LEN]; ///< Payload data, ALIGNMENT IMPORTANT ON MCU + uint8_t ck_a; ///< Checksum high byte + uint8_t ck_b; ///< Checksum low byte +} mavlink_message_t; + +typedef enum { + MAVLINK_COMM_0, + MAVLINK_COMM_1, + MAVLINK_COMM_NB, + MAVLINK_COMM_NB_HIGH = 16 +} mavlink_channel_t; + +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 ck_a; ///< Checksum byte 1 + uint8_t ck_b; ///< Checksum byte 2 + 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_seq; ///< Sequence number of last packet + uint16_t packet_rx_success_count; ///< Received packets + uint16_t packet_rx_drop_count; ///< Number of packet drops +} mavlink_status_t; + +#endif /* MAVLINK_TYPES_H_ */ diff --git a/libraries/mavlink/include/pixhawk/mavlink.h b/libraries/mavlink/include/pixhawk/mavlink.h new file mode 100644 index 0000000000..01989a3a1b --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Sunday, October 24 2010, 08:46 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "pixhawk.h" + +#endif diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_attitude_control.h b/libraries/mavlink/include/pixhawk/mavlink_msg_attitude_control.h new file mode 100644 index 0000000000..f1880b3427 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_attitude_control.h @@ -0,0 +1,191 @@ +// MESSAGE ATTITUDE_CONTROL PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_CONTROL 85 + +typedef struct __mavlink_attitude_control_t +{ + uint8_t target; ///< The system to be controlled + float roll; ///< roll + float pitch; ///< pitch + float yaw; ///< yaw + float thrust; ///< thrust + uint8_t 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 + +} mavlink_attitude_control_t; + + + +/** + * @brief Send a attitude_control message + * + * @param target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system to be controlled + i += put_float_by_index(roll, i, msg->payload); //roll + i += put_float_by_index(pitch, i, msg->payload); //pitch + i += put_float_by_index(yaw, i, msg->payload); //yaw + i += put_float_by_index(thrust, i, msg->payload); //thrust + i += put_uint8_t_by_index(roll_manual, i, msg->payload); //roll control enabled auto:0, manual:1 + i += put_uint8_t_by_index(pitch_manual, i, msg->payload); //pitch auto:0, manual:1 + i += put_uint8_t_by_index(yaw_manual, i, msg->payload); //yaw auto:0, manual:1 + i += put_uint8_t_by_index(thrust_manual, i, msg->payload); //thrust auto:0, manual:1 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_control_t* attitude_control) +{ + return mavlink_msg_attitude_control_pack(system_id, component_id, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ + mavlink_message_t msg; + mavlink_msg_attitude_control_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ATTITUDE_CONTROL UNPACKING + +/** + * @brief Get field target from attitude_control message + * + * @return The system to be controlled + */ +static inline uint8_t mavlink_msg_attitude_control_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field roll from attitude_control message + * + * @return roll + */ +static inline float mavlink_msg_attitude_control_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from attitude_control message + * + * @return pitch + */ +static inline float mavlink_msg_attitude_control_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from attitude_control message + * + * @return yaw + */ +static inline float mavlink_msg_attitude_control_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field thrust from attitude_control message + * + * @return thrust + */ +static inline float mavlink_msg_attitude_control_get_thrust(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field roll_manual from attitude_control message + * + * @return roll control enabled auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_control_get_roll_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; +} + +/** + * @brief Get field pitch_manual from attitude_control message + * + * @return pitch auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_control_get_pitch_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field yaw_manual from attitude_control message + * + * @return yaw auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_control_get_yaw_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field thrust_manual from attitude_control message + * + * @return thrust auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_control_get_thrust_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_attitude_control_decode(const mavlink_message_t* msg, mavlink_attitude_control_t* attitude_control) +{ + attitude_control->target = mavlink_msg_attitude_control_get_target(msg); + attitude_control->roll = mavlink_msg_attitude_control_get_roll(msg); + attitude_control->pitch = mavlink_msg_attitude_control_get_pitch(msg); + attitude_control->yaw = mavlink_msg_attitude_control_get_yaw(msg); + attitude_control->thrust = mavlink_msg_attitude_control_get_thrust(msg); + attitude_control->roll_manual = mavlink_msg_attitude_control_get_roll_manual(msg); + attitude_control->pitch_manual = mavlink_msg_attitude_control_get_pitch_manual(msg); + attitude_control->yaw_manual = mavlink_msg_attitude_control_get_yaw_manual(msg); + attitude_control->thrust_manual = mavlink_msg_attitude_control_get_thrust_manual(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_aux_status.h b/libraries/mavlink/include/pixhawk/mavlink_msg_aux_status.h new file mode 100644 index 0000000000..7ed8871e4f --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_aux_status.h @@ -0,0 +1,147 @@ +// MESSAGE AUX_STATUS PACKING + +#define MAVLINK_MSG_ID_AUX_STATUS 142 + +typedef struct __mavlink_aux_status_t +{ + uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + uint16_t i2c0_err_count; ///< Number of I2C errors since startup + uint16_t i2c1_err_count; ///< Number of I2C errors since startup + uint16_t spi0_err_count; ///< Number of I2C errors since startup + uint16_t spi1_err_count; ///< Number of I2C errors since startup + uint16_t uart_total_err_count; ///< Number of I2C errors since startup + +} mavlink_aux_status_t; + + + +/** + * @brief Send a aux_status message + * + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param i2c0_err_count Number of I2C errors since startup + * @param i2c1_err_count Number of I2C errors since startup + * @param spi0_err_count Number of I2C errors since startup + * @param spi1_err_count Number of I2C errors since startup + * @param uart_total_err_count Number of I2C errors since startup + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_aux_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_AUX_STATUS; + + i += put_uint16_t_by_index(load, i, msg->payload); //Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); //Number of I2C errors since startup + i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); //Number of I2C errors since startup + i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); //Number of I2C errors since startup + i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); //Number of I2C errors since startup + i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); //Number of I2C errors since startup + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_aux_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aux_status_t* aux_status) +{ + return mavlink_msg_aux_status_pack(system_id, component_id, msg, aux_status->load, aux_status->i2c0_err_count, aux_status->i2c1_err_count, aux_status->spi0_err_count, aux_status->spi1_err_count, aux_status->uart_total_err_count); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_aux_status_send(mavlink_channel_t chan, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count) +{ + mavlink_message_t msg; + mavlink_msg_aux_status_pack(mavlink_system.sysid, mavlink_system.compid, &msg, load, i2c0_err_count, i2c1_err_count, spi0_err_count, spi1_err_count, uart_total_err_count); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE AUX_STATUS UNPACKING + +/** + * @brief Get field load from aux_status message + * + * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + */ +static inline uint16_t mavlink_msg_aux_status_get_load(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field i2c0_err_count from aux_status message + * + * @return Number of I2C errors since startup + */ +static inline uint16_t mavlink_msg_aux_status_get_i2c0_err_count(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field i2c1_err_count from aux_status message + * + * @return Number of I2C errors since startup + */ +static inline uint16_t mavlink_msg_aux_status_get_i2c1_err_count(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field spi0_err_count from aux_status message + * + * @return Number of I2C errors since startup + */ +static inline uint16_t mavlink_msg_aux_status_get_spi0_err_count(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field spi1_err_count from aux_status message + * + * @return Number of I2C errors since startup + */ +static inline uint16_t mavlink_msg_aux_status_get_spi1_err_count(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field uart_total_err_count from aux_status message + * + * @return Number of I2C errors since startup + */ +static inline uint16_t mavlink_msg_aux_status_get_uart_total_err_count(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_aux_status_decode(const mavlink_message_t* msg, mavlink_aux_status_t* aux_status) +{ + aux_status->load = mavlink_msg_aux_status_get_load(msg); + aux_status->i2c0_err_count = mavlink_msg_aux_status_get_i2c0_err_count(msg); + aux_status->i2c1_err_count = mavlink_msg_aux_status_get_i2c1_err_count(msg); + aux_status->spi0_err_count = mavlink_msg_aux_status_get_spi0_err_count(msg); + aux_status->spi1_err_count = mavlink_msg_aux_status_get_spi1_err_count(msg); + aux_status->uart_total_err_count = mavlink_msg_aux_status_get_uart_total_err_count(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_control_status.h b/libraries/mavlink/include/pixhawk/mavlink_msg_control_status.h new file mode 100644 index 0000000000..ec93a38e4b --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_control_status.h @@ -0,0 +1,143 @@ +// MESSAGE CONTROL_STATUS PACKING + +#define MAVLINK_MSG_ID_CONTROL_STATUS 143 + +typedef struct __mavlink_control_status_t +{ + uint8_t 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 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 + +} mavlink_control_status_t; + + + +/** + * @brief Send a control_status message + * + * @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + * @param control_att 0: Attitude control disabled, 1: enabled + * @param control_pos_xy 0: X, Y position control disabled, 1: enabled + * @param control_pos_z 0: Z position control disabled, 1: enabled + * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_control_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS; + + i += put_uint8_t_by_index(position_fix, i, msg->payload); //Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + i += put_uint8_t_by_index(vision_fix, i, msg->payload); //Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + i += put_uint8_t_by_index(gps_fix, i, msg->payload); //GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + i += put_uint8_t_by_index(control_att, i, msg->payload); //0: Attitude control disabled, 1: enabled + i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); //0: X, Y position control disabled, 1: enabled + i += put_uint8_t_by_index(control_pos_z, i, msg->payload); //0: Z position control disabled, 1: enabled + i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); //0: Yaw angle control disabled, 1: enabled + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_control_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_status_t* control_status) +{ + return mavlink_msg_control_status_pack(system_id, component_id, msg, control_status->position_fix, control_status->vision_fix, control_status->gps_fix, control_status->control_att, control_status->control_pos_xy, control_status->control_pos_z, control_status->control_pos_yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_control_status_send(mavlink_channel_t chan, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw) +{ + mavlink_message_t msg; + mavlink_msg_control_status_pack(mavlink_system.sysid, mavlink_system.compid, &msg, position_fix, vision_fix, gps_fix, control_att, control_pos_xy, control_pos_z, control_pos_yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE CONTROL_STATUS UNPACKING + +/** + * @brief Get field position_fix from control_status message + * + * @return Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + */ +static inline uint8_t mavlink_msg_control_status_get_position_fix(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field vision_fix from control_status message + * + * @return Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + */ +static inline uint8_t mavlink_msg_control_status_get_vision_fix(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field gps_fix from control_status message + * + * @return GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + */ +static inline uint8_t mavlink_msg_control_status_get_gps_fix(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field control_att from control_status message + * + * @return 0: Attitude control disabled, 1: enabled + */ +static inline uint8_t mavlink_msg_control_status_get_control_att(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field control_pos_xy from control_status message + * + * @return 0: X, Y position control disabled, 1: enabled + */ +static inline uint8_t mavlink_msg_control_status_get_control_pos_xy(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field control_pos_z from control_status message + * + * @return 0: Z position control disabled, 1: enabled + */ +static inline uint8_t mavlink_msg_control_status_get_control_pos_z(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field control_pos_yaw from control_status message + * + * @return 0: Yaw angle control disabled, 1: enabled + */ +static inline uint8_t mavlink_msg_control_status_get_control_pos_yaw(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_control_status_decode(const mavlink_message_t* msg, mavlink_control_status_t* control_status) +{ + control_status->position_fix = mavlink_msg_control_status_get_position_fix(msg); + control_status->vision_fix = mavlink_msg_control_status_get_vision_fix(msg); + control_status->gps_fix = mavlink_msg_control_status_get_gps_fix(msg); + control_status->control_att = mavlink_msg_control_status_get_control_att(msg); + control_status->control_pos_xy = mavlink_msg_control_status_get_control_pos_xy(msg); + control_status->control_pos_z = mavlink_msg_control_status_get_control_pos_z(msg); + control_status->control_pos_yaw = mavlink_msg_control_status_get_control_pos_yaw(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_debug_vect.h b/libraries/mavlink/include/pixhawk/mavlink_msg_debug_vect.h new file mode 100644 index 0000000000..d34f4a73f8 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_debug_vect.h @@ -0,0 +1,142 @@ +// MESSAGE DEBUG_VECT PACKING + +#define MAVLINK_MSG_ID_DEBUG_VECT 90 + +typedef struct __mavlink_debug_vect_t +{ + int8_t name[10]; ///< Name + uint64_t usec; ///< Timestamp + float x; ///< x + float y; ///< y + float z; ///< z + +} mavlink_debug_vect_t; + +#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10 + + +/** + * @brief Send a debug_vect message + * + * @param name Name + * @param usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const int8_t* name, uint64_t usec, float x, float y, float z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; + + i += put_array_by_index(name, 10, i, msg->payload); //Name + i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp + i += put_float_by_index(x, i, msg->payload); //x + i += put_float_by_index(y, i, msg->payload); //y + i += put_float_by_index(z, i, msg->payload); //z + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) +{ + return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const int8_t* name, uint64_t usec, float x, float y, float z) +{ + mavlink_message_t msg; + mavlink_msg_debug_vect_pack(mavlink_system.sysid, mavlink_system.compid, &msg, name, usec, x, y, z); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE DEBUG_VECT UNPACKING + +/** + * @brief Get field name from debug_vect message + * + * @return Name + */ +static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload, 10); + return 10; +} + +/** + * @brief Get field usec from debug_vect message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload+10)[0]; + r.b[6] = (msg->payload+10)[1]; + r.b[5] = (msg->payload+10)[2]; + r.b[4] = (msg->payload+10)[3]; + r.b[3] = (msg->payload+10)[4]; + r.b[2] = (msg->payload+10)[5]; + r.b[1] = (msg->payload+10)[6]; + r.b[0] = (msg->payload+10)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field x from debug_vect message + * + * @return x + */ +static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+10+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+10+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+10+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+10+sizeof(uint64_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from debug_vect message + * + * @return y + */ +static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from debug_vect message + * + * @return z + */ +static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect) +{ + mavlink_msg_debug_vect_get_name(msg, debug_vect->name); + debug_vect->usec = mavlink_msg_debug_vect_get_usec(msg); + debug_vect->x = mavlink_msg_debug_vect_get_x(msg); + debug_vect->y = mavlink_msg_debug_vect_get_y(msg); + debug_vect->z = mavlink_msg_debug_vect_get_z(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_image_available.h b/libraries/mavlink/include/pixhawk/mavlink_msg_image_available.h new file mode 100644 index 0000000000..4d60f06bc6 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_image_available.h @@ -0,0 +1,326 @@ +// MESSAGE IMAGE_AVAILABLE PACKING + +#define MAVLINK_MSG_ID_IMAGE_AVAILABLE 103 + +typedef struct __mavlink_image_available_t +{ + uint64_t cam_id; ///< Camera id + uint8_t cam_no; ///< Camera # (starts with 0) + uint64_t timestamp; ///< Timestamp + uint64_t valid_until; ///< Until which timestamp this buffer will stay valid + uint32_t img_seq; ///< The image sequence number + uint32_t img_buf_index; ///< Position of the image in the buffer, starts with 0 + uint16_t width; ///< Image width + uint16_t height; ///< Image height + uint16_t depth; ///< Image depth + uint8_t channels; ///< Image channels + uint32_t key; ///< Shared memory area key + uint32_t exposure; ///< Exposure time, in microseconds + float gain; ///< Camera gain + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + +} mavlink_image_available_t; + + + +/** + * @brief Send a image_available message + * + * @param cam_id Camera id + * @param cam_no Camera # (starts with 0) + * @param timestamp Timestamp + * @param valid_until Until which timestamp this buffer will stay valid + * @param img_seq The image sequence number + * @param img_buf_index Position of the image in the buffer, starts with 0 + * @param width Image width + * @param height Image height + * @param depth Image depth + * @param channels Image channels + * @param key Shared memory area key + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; + + i += put_uint64_t_by_index(cam_id, i, msg->payload); //Camera id + i += put_uint8_t_by_index(cam_no, i, msg->payload); //Camera # (starts with 0) + i += put_uint64_t_by_index(timestamp, i, msg->payload); //Timestamp + i += put_uint64_t_by_index(valid_until, i, msg->payload); //Until which timestamp this buffer will stay valid + i += put_uint32_t_by_index(img_seq, i, msg->payload); //The image sequence number + i += put_uint32_t_by_index(img_buf_index, i, msg->payload); //Position of the image in the buffer, starts with 0 + i += put_uint16_t_by_index(width, i, msg->payload); //Image width + i += put_uint16_t_by_index(height, i, msg->payload); //Image height + i += put_uint16_t_by_index(depth, i, msg->payload); //Image depth + i += put_uint8_t_by_index(channels, i, msg->payload); //Image channels + i += put_uint32_t_by_index(key, i, msg->payload); //Shared memory area key + i += put_uint32_t_by_index(exposure, i, msg->payload); //Exposure time, in microseconds + i += put_float_by_index(gain, i, msg->payload); //Camera gain + i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_available_t* image_available) +{ + return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch) +{ + mavlink_message_t msg; + mavlink_msg_image_available_pack(mavlink_system.sysid, mavlink_system.compid, &msg, cam_id, cam_no, timestamp, valid_until, img_seq, img_buf_index, width, height, depth, channels, key, exposure, gain, roll, pitch); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE IMAGE_AVAILABLE UNPACKING + +/** + * @brief Get field cam_id from image_available message + * + * @return Camera id + */ +static inline uint64_t mavlink_msg_image_available_get_cam_id(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field cam_no from image_available message + * + * @return Camera # (starts with 0) + */ +static inline uint8_t mavlink_msg_image_available_get_cam_no(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint64_t))[0]; +} + +/** + * @brief Get field timestamp from image_available message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_image_available_get_timestamp(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0]; + r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1]; + r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2]; + r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3]; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[4]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[5]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[6]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field valid_until from image_available message + * + * @return Until which timestamp this buffer will stay valid + */ +static inline uint64_t mavlink_msg_image_available_get_valid_until(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[0]; + r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[1]; + r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[2]; + r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[3]; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[4]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[5]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[6]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field img_seq from image_available message + * + * @return The image sequence number + */ +static inline uint32_t mavlink_msg_image_available_get_img_seq(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[3]; + return (uint32_t)r.i; +} + +/** + * @brief Get field img_buf_index from image_available message + * + * @return Position of the image in the buffer, starts with 0 + */ +static inline uint32_t mavlink_msg_image_available_get_img_buf_index(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[3]; + return (uint32_t)r.i; +} + +/** + * @brief Get field width from image_available message + * + * @return Image width + */ +static inline uint16_t mavlink_msg_image_available_get_width(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field height from image_available message + * + * @return Image height + */ +static inline uint16_t mavlink_msg_image_available_get_height(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field depth from image_available message + * + * @return Image depth + */ +static inline uint16_t mavlink_msg_image_available_get_depth(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field channels from image_available message + * + * @return Image channels + */ +static inline uint8_t mavlink_msg_image_available_get_channels(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; +} + +/** + * @brief Get field key from image_available message + * + * @return Shared memory area key + */ +static inline uint32_t mavlink_msg_image_available_get_key(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[3]; + return (uint32_t)r.i; +} + +/** + * @brief Get field exposure from image_available message + * + * @return Exposure time, in microseconds + */ +static inline uint32_t mavlink_msg_image_available_get_exposure(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[3]; + return (uint32_t)r.i; +} + +/** + * @brief Get field gain from image_available message + * + * @return Camera gain + */ +static inline float mavlink_msg_image_available_get_gain(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field roll from image_available message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_image_available_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from image_available message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_image_available_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_image_available_decode(const mavlink_message_t* msg, mavlink_image_available_t* image_available) +{ + image_available->cam_id = mavlink_msg_image_available_get_cam_id(msg); + image_available->cam_no = mavlink_msg_image_available_get_cam_no(msg); + image_available->timestamp = mavlink_msg_image_available_get_timestamp(msg); + image_available->valid_until = mavlink_msg_image_available_get_valid_until(msg); + image_available->img_seq = mavlink_msg_image_available_get_img_seq(msg); + image_available->img_buf_index = mavlink_msg_image_available_get_img_buf_index(msg); + image_available->width = mavlink_msg_image_available_get_width(msg); + image_available->height = mavlink_msg_image_available_get_height(msg); + image_available->depth = mavlink_msg_image_available_get_depth(msg); + image_available->channels = mavlink_msg_image_available_get_channels(msg); + image_available->key = mavlink_msg_image_available_get_key(msg); + image_available->exposure = mavlink_msg_image_available_get_exposure(msg); + image_available->gain = mavlink_msg_image_available_get_gain(msg); + image_available->roll = mavlink_msg_image_available_get_roll(msg); + image_available->pitch = mavlink_msg_image_available_get_pitch(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_image_trigger_control.h b/libraries/mavlink/include/pixhawk/mavlink_msg_image_trigger_control.h new file mode 100644 index 0000000000..f7e23dc339 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_image_trigger_control.h @@ -0,0 +1,59 @@ +// MESSAGE IMAGE_TRIGGER_CONTROL PACKING + +#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL 102 + +typedef struct __mavlink_image_trigger_control_t +{ + uint8_t enable; ///< 0 to disable, 1 to enable + +} mavlink_image_trigger_control_t; + + + +/** + * @brief Send a image_trigger_control message + * + * @param enable 0 to disable, 1 to enable + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t enable) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; + + i += put_uint8_t_by_index(enable, i, msg->payload); //0 to disable, 1 to enable + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_trigger_control_t* image_trigger_control) +{ + return mavlink_msg_image_trigger_control_pack(system_id, component_id, msg, image_trigger_control->enable); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan, uint8_t enable) +{ + mavlink_message_t msg; + mavlink_msg_image_trigger_control_pack(mavlink_system.sysid, mavlink_system.compid, &msg, enable); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE IMAGE_TRIGGER_CONTROL UNPACKING + +/** + * @brief Get field enable from image_trigger_control message + * + * @return 0 to disable, 1 to enable + */ +static inline uint8_t mavlink_msg_image_trigger_control_get_enable(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +static inline void mavlink_msg_image_trigger_control_decode(const mavlink_message_t* msg, mavlink_image_trigger_control_t* image_trigger_control) +{ + image_trigger_control->enable = mavlink_msg_image_trigger_control_get_enable(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_image_triggered.h b/libraries/mavlink/include/pixhawk/mavlink_msg_image_triggered.h new file mode 100644 index 0000000000..23af0af044 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_image_triggered.h @@ -0,0 +1,125 @@ +// MESSAGE IMAGE_TRIGGERED PACKING + +#define MAVLINK_MSG_ID_IMAGE_TRIGGERED 101 + +typedef struct __mavlink_image_triggered_t +{ + uint64_t timestamp; ///< Timestamp + uint32_t seq; ///< IMU seq + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + +} mavlink_image_triggered_t; + + + +/** + * @brief Send a image_triggered message + * + * @param timestamp Timestamp + * @param seq IMU seq + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; + + i += put_uint64_t_by_index(timestamp, i, msg->payload); //Timestamp + i += put_uint32_t_by_index(seq, i, msg->payload); //IMU seq + i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered) +{ + return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch) +{ + mavlink_message_t msg; + mavlink_msg_image_triggered_pack(mavlink_system.sysid, mavlink_system.compid, &msg, timestamp, seq, roll, pitch); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE IMAGE_TRIGGERED UNPACKING + +/** + * @brief Get field timestamp from image_triggered message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_image_triggered_get_timestamp(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field seq from image_triggered message + * + * @return IMU seq + */ +static inline uint32_t mavlink_msg_image_triggered_get_seq(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (uint32_t)r.i; +} + +/** + * @brief Get field roll from image_triggered message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_image_triggered_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from image_triggered message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_image_triggered_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* msg, mavlink_image_triggered_t* image_triggered) +{ + image_triggered->timestamp = mavlink_msg_image_triggered_get_timestamp(msg); + image_triggered->seq = mavlink_msg_image_triggered_get_seq(msg); + image_triggered->roll = mavlink_msg_image_triggered_get_roll(msg); + image_triggered->pitch = mavlink_msg_image_triggered_get_pitch(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_manual_control.h b/libraries/mavlink/include/pixhawk/mavlink_msg_manual_control.h new file mode 100644 index 0000000000..b8fb08f6ee --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_manual_control.h @@ -0,0 +1,191 @@ +// MESSAGE MANUAL_CONTROL PACKING + +#define MAVLINK_MSG_ID_MANUAL_CONTROL 84 + +typedef struct __mavlink_manual_control_t +{ + uint8_t target; ///< The system to be controlled + float roll; ///< roll + float pitch; ///< pitch + float yaw; ///< yaw + float thrust; ///< thrust + uint8_t 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 + +} mavlink_manual_control_t; + + + +/** + * @brief Send a manual_control message + * + * @param target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system to be controlled + i += put_float_by_index(roll, i, msg->payload); //roll + i += put_float_by_index(pitch, i, msg->payload); //pitch + i += put_float_by_index(yaw, i, msg->payload); //yaw + i += put_float_by_index(thrust, i, msg->payload); //thrust + i += put_uint8_t_by_index(roll_manual, i, msg->payload); //roll control enabled auto:0, manual:1 + i += put_uint8_t_by_index(pitch_manual, i, msg->payload); //pitch auto:0, manual:1 + i += put_uint8_t_by_index(yaw_manual, i, msg->payload); //yaw auto:0, manual:1 + i += put_uint8_t_by_index(thrust_manual, i, msg->payload); //thrust auto:0, manual:1 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) +{ + return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->roll, manual_control->pitch, manual_control->yaw, manual_control->thrust, manual_control->roll_manual, manual_control->pitch_manual, manual_control->yaw_manual, manual_control->thrust_manual); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ + mavlink_message_t msg; + mavlink_msg_manual_control_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE MANUAL_CONTROL UNPACKING + +/** + * @brief Get field target from manual_control message + * + * @return The system to be controlled + */ +static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field roll from manual_control message + * + * @return roll + */ +static inline float mavlink_msg_manual_control_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from manual_control message + * + * @return pitch + */ +static inline float mavlink_msg_manual_control_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from manual_control message + * + * @return yaw + */ +static inline float mavlink_msg_manual_control_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field thrust from manual_control message + * + * @return thrust + */ +static inline float mavlink_msg_manual_control_get_thrust(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field roll_manual from manual_control message + * + * @return roll control enabled auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_roll_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; +} + +/** + * @brief Get field pitch_manual from manual_control message + * + * @return pitch auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_pitch_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field yaw_manual from manual_control message + * + * @return yaw auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_yaw_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field thrust_manual from manual_control message + * + * @return thrust auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_thrust_manual(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control) +{ + manual_control->target = mavlink_msg_manual_control_get_target(msg); + manual_control->roll = mavlink_msg_manual_control_get_roll(msg); + manual_control->pitch = mavlink_msg_manual_control_get_pitch(msg); + manual_control->yaw = mavlink_msg_manual_control_get_yaw(msg); + manual_control->thrust = mavlink_msg_manual_control_get_thrust(msg); + manual_control->roll_manual = mavlink_msg_manual_control_get_roll_manual(msg); + manual_control->pitch_manual = mavlink_msg_manual_control_get_pitch_manual(msg); + manual_control->yaw_manual = mavlink_msg_manual_control_get_yaw_manual(msg); + manual_control->thrust_manual = mavlink_msg_manual_control_get_thrust_manual(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_marker.h b/libraries/mavlink/include/pixhawk/mavlink_msg_marker.h new file mode 100644 index 0000000000..4dd50f134f --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_marker.h @@ -0,0 +1,176 @@ +// MESSAGE MARKER PACKING + +#define MAVLINK_MSG_ID_MARKER 130 + +typedef struct __mavlink_marker_t +{ + uint16_t id; ///< ID + float x; ///< x position + float y; ///< y position + float z; ///< z position + float roll; ///< roll orientation + float pitch; ///< pitch orientation + float yaw; ///< yaw orientation + +} mavlink_marker_t; + + + +/** + * @brief Send a marker message + * + * @param id ID + * @param x x position + * @param y y position + * @param z z position + * @param roll roll orientation + * @param pitch pitch orientation + * @param yaw yaw orientation + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_MARKER; + + i += put_uint16_t_by_index(id, i, msg->payload); //ID + i += put_float_by_index(x, i, msg->payload); //x position + i += put_float_by_index(y, i, msg->payload); //y position + i += put_float_by_index(z, i, msg->payload); //z position + i += put_float_by_index(roll, i, msg->payload); //roll orientation + i += put_float_by_index(pitch, i, msg->payload); //pitch orientation + i += put_float_by_index(yaw, i, msg->payload); //yaw orientation + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_marker_t* marker) +{ + return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_marker_pack(mavlink_system.sysid, mavlink_system.compid, &msg, id, x, y, z, roll, pitch, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE MARKER UNPACKING + +/** + * @brief Get field id from marker message + * + * @return ID + */ +static inline uint16_t mavlink_msg_marker_get_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field x from marker message + * + * @return x position + */ +static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from marker message + * + * @return y position + */ +static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from marker message + * + * @return z position + */ +static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field roll from marker message + * + * @return roll orientation + */ +static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from marker message + * + * @return pitch orientation + */ +static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from marker message + * + * @return yaw orientation + */ +static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavlink_marker_t* marker) +{ + marker->id = mavlink_msg_marker_get_id(msg); + marker->x = mavlink_msg_marker_get_x(msg); + marker->y = mavlink_msg_marker_get_y(msg); + marker->z = mavlink_msg_marker_get_z(msg); + marker->roll = mavlink_msg_marker_get_roll(msg); + marker->pitch = mavlink_msg_marker_get_pitch(msg); + marker->yaw = mavlink_msg_marker_get_yaw(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_pattern_detected.h b/libraries/mavlink/include/pixhawk/mavlink_msg_pattern_detected.h new file mode 100644 index 0000000000..28965642b7 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_pattern_detected.h @@ -0,0 +1,109 @@ +// MESSAGE PATTERN_DETECTED PACKING + +#define MAVLINK_MSG_ID_PATTERN_DETECTED 160 + +typedef struct __mavlink_pattern_detected_t +{ + uint8_t type; ///< 0: Pattern, 1: Letter + float confidence; ///< Confidence of detection + int8_t file[100]; ///< Pattern file name + uint8_t detected; ///< Accepted as true detection, 0 no, 1 yes + +} mavlink_pattern_detected_t; + +#define MAVLINK_MSG_PATTERN_DETECTED_FIELD_FILE_LEN 100 + + +/** + * @brief Send a pattern_detected message + * + * @param type 0: Pattern, 1: Letter + * @param confidence Confidence of detection + * @param file Pattern file name + * @param detected Accepted as true detection, 0 no, 1 yes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, float confidence, const int8_t* file, uint8_t detected) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; + + i += put_uint8_t_by_index(type, i, msg->payload); //0: Pattern, 1: Letter + i += put_float_by_index(confidence, i, msg->payload); //Confidence of detection + i += put_array_by_index(file, 100, i, msg->payload); //Pattern file name + i += put_uint8_t_by_index(detected, i, msg->payload); //Accepted as true detection, 0 no, 1 yes + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pattern_detected_t* pattern_detected) +{ + return mavlink_msg_pattern_detected_pack(system_id, component_id, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const int8_t* file, uint8_t detected) +{ + mavlink_message_t msg; + mavlink_msg_pattern_detected_pack(mavlink_system.sysid, mavlink_system.compid, &msg, type, confidence, file, detected); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PATTERN_DETECTED UNPACKING + +/** + * @brief Get field type from pattern_detected message + * + * @return 0: Pattern, 1: Letter + */ +static inline uint8_t mavlink_msg_pattern_detected_get_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field confidence from pattern_detected message + * + * @return Confidence of detection + */ +static inline float mavlink_msg_pattern_detected_get_confidence(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field file from pattern_detected message + * + * @return Pattern file name + */ +static inline uint16_t mavlink_msg_pattern_detected_get_file(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(float), 100); + return 100; +} + +/** + * @brief Get field detected from pattern_detected message + * + * @return Accepted as true detection, 0 no, 1 yes + */ +static inline uint8_t mavlink_msg_pattern_detected_get_detected(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+100)[0]; +} + +static inline void mavlink_msg_pattern_detected_decode(const mavlink_message_t* msg, mavlink_pattern_detected_t* pattern_detected) +{ + pattern_detected->type = mavlink_msg_pattern_detected_get_type(msg); + pattern_detected->confidence = mavlink_msg_pattern_detected_get_confidence(msg); + mavlink_msg_pattern_detected_get_file(msg, pattern_detected->file); + pattern_detected->detected = mavlink_msg_pattern_detected_get_detected(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_position_control_offset_set.h b/libraries/mavlink/include/pixhawk/mavlink_msg_position_control_offset_set.h new file mode 100644 index 0000000000..6ccbee3c37 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_position_control_offset_set.h @@ -0,0 +1,149 @@ +// MESSAGE POSITION_CONTROL_OFFSET_SET PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET 154 + +typedef struct __mavlink_position_control_offset_set_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + float x; ///< x position offset + float y; ///< y position offset + float z; ///< z position offset + float yaw; ///< yaw orientation offset in radians, 0 = NORTH + +} mavlink_position_control_offset_set_t; + + + +/** + * @brief Send a position_control_offset_set message + * + * @param target_system System ID + * @param target_component Component ID + * @param x x position offset + * @param y y position offset + * @param z z position offset + * @param yaw yaw orientation offset in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_offset_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_float_by_index(x, i, msg->payload); //x position offset + i += put_float_by_index(y, i, msg->payload); //y position offset + i += put_float_by_index(z, i, msg->payload); //z position offset + i += put_float_by_index(yaw, i, msg->payload); //yaw orientation offset in radians, 0 = NORTH + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_position_control_offset_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_offset_set_t* position_control_offset_set) +{ + return mavlink_msg_position_control_offset_set_pack(system_id, component_id, msg, position_control_offset_set->target_system, position_control_offset_set->target_component, position_control_offset_set->x, position_control_offset_set->y, position_control_offset_set->z, position_control_offset_set->yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_control_offset_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_position_control_offset_set_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POSITION_CONTROL_OFFSET_SET UNPACKING + +/** + * @brief Get field target_system from position_control_offset_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_position_control_offset_set_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from position_control_offset_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_position_control_offset_set_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field x from position_control_offset_set message + * + * @return x position offset + */ +static inline float mavlink_msg_position_control_offset_set_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from position_control_offset_set message + * + * @return y position offset + */ +static inline float mavlink_msg_position_control_offset_set_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from position_control_offset_set message + * + * @return z position offset + */ +static inline float mavlink_msg_position_control_offset_set_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from position_control_offset_set message + * + * @return yaw orientation offset in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_control_offset_set_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_position_control_offset_set_decode(const mavlink_message_t* msg, mavlink_position_control_offset_set_t* position_control_offset_set) +{ + position_control_offset_set->target_system = mavlink_msg_position_control_offset_set_get_target_system(msg); + position_control_offset_set->target_component = mavlink_msg_position_control_offset_set_get_target_component(msg); + position_control_offset_set->x = mavlink_msg_position_control_offset_set_get_x(msg); + position_control_offset_set->y = mavlink_msg_position_control_offset_set_get_y(msg); + position_control_offset_set->z = mavlink_msg_position_control_offset_set_get_z(msg); + position_control_offset_set->yaw = mavlink_msg_position_control_offset_set_get_yaw(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint.h b/libraries/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint.h new file mode 100644 index 0000000000..86d9beb2ee --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint.h @@ -0,0 +1,138 @@ +// MESSAGE POSITION_CONTROL_SETPOINT PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT 121 + +typedef struct __mavlink_position_control_setpoint_t +{ + uint16_t id; ///< ID of waypoint, 0 for plain position + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< yaw orientation in radians, 0 = NORTH + +} mavlink_position_control_setpoint_t; + + + +/** + * @brief Send a position_control_setpoint message + * + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; + + i += put_uint16_t_by_index(id, i, msg->payload); //ID of waypoint, 0 for plain position + i += put_float_by_index(x, i, msg->payload); //x position + i += put_float_by_index(y, i, msg->payload); //y position + i += put_float_by_index(z, i, msg->payload); //z position + i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_t* position_control_setpoint) +{ + return mavlink_msg_position_control_setpoint_pack(system_id, component_id, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_position_control_setpoint_pack(mavlink_system.sysid, mavlink_system.compid, &msg, id, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POSITION_CONTROL_SETPOINT UNPACKING + +/** + * @brief Get field id from position_control_setpoint message + * + * @return ID of waypoint, 0 for plain position + */ +static inline uint16_t mavlink_msg_position_control_setpoint_get_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field x from position_control_setpoint message + * + * @return x position + */ +static inline float mavlink_msg_position_control_setpoint_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from position_control_setpoint message + * + * @return y position + */ +static inline float mavlink_msg_position_control_setpoint_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from position_control_setpoint message + * + * @return z position + */ +static inline float mavlink_msg_position_control_setpoint_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from position_control_setpoint message + * + * @return yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_control_setpoint_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_position_control_setpoint_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_t* position_control_setpoint) +{ + position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg); + position_control_setpoint->x = mavlink_msg_position_control_setpoint_get_x(msg); + position_control_setpoint->y = mavlink_msg_position_control_setpoint_get_y(msg); + position_control_setpoint->z = mavlink_msg_position_control_setpoint_get_z(msg); + position_control_setpoint->yaw = mavlink_msg_position_control_setpoint_get_yaw(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h b/libraries/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h new file mode 100644 index 0000000000..eb37643615 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h @@ -0,0 +1,166 @@ +// MESSAGE POSITION_CONTROL_SETPOINT_SET PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET 120 + +typedef struct __mavlink_position_control_setpoint_set_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint16_t id; ///< ID of waypoint, 0 for plain position + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< yaw orientation in radians, 0 = NORTH + +} mavlink_position_control_setpoint_set_t; + + + +/** + * @brief Send a position_control_setpoint_set message + * + * @param target_system System ID + * @param target_component Component ID + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID + i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID + i += put_uint16_t_by_index(id, i, msg->payload); //ID of waypoint, 0 for plain position + i += put_float_by_index(x, i, msg->payload); //x position + i += put_float_by_index(y, i, msg->payload); //y position + i += put_float_by_index(z, i, msg->payload); //z position + i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_position_control_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_set_t* position_control_setpoint_set) +{ + return mavlink_msg_position_control_setpoint_set_pack(system_id, component_id, msg, position_control_setpoint_set->target_system, position_control_setpoint_set->target_component, position_control_setpoint_set->id, position_control_setpoint_set->x, position_control_setpoint_set->y, position_control_setpoint_set->z, position_control_setpoint_set->yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_control_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_position_control_setpoint_set_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, id, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POSITION_CONTROL_SETPOINT_SET UNPACKING + +/** + * @brief Get field target_system from position_control_setpoint_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from position_control_setpoint_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field id from position_control_setpoint_set message + * + * @return ID of waypoint, 0 for plain position + */ +static inline uint16_t mavlink_msg_position_control_setpoint_set_get_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field x from position_control_setpoint_set message + * + * @return x position + */ +static inline float mavlink_msg_position_control_setpoint_set_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from position_control_setpoint_set message + * + * @return y position + */ +static inline float mavlink_msg_position_control_setpoint_set_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from position_control_setpoint_set message + * + * @return z position + */ +static inline float mavlink_msg_position_control_setpoint_set_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from position_control_setpoint_set message + * + * @return yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_control_setpoint_set_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_position_control_setpoint_set_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_set_t* position_control_setpoint_set) +{ + position_control_setpoint_set->target_system = mavlink_msg_position_control_setpoint_set_get_target_system(msg); + position_control_setpoint_set->target_component = mavlink_msg_position_control_setpoint_set_get_target_component(msg); + position_control_setpoint_set->id = mavlink_msg_position_control_setpoint_set_get_id(msg); + position_control_setpoint_set->x = mavlink_msg_position_control_setpoint_set_get_x(msg); + position_control_setpoint_set->y = mavlink_msg_position_control_setpoint_set_get_y(msg); + position_control_setpoint_set->z = mavlink_msg_position_control_setpoint_set_get_z(msg); + position_control_setpoint_set->yaw = mavlink_msg_position_control_setpoint_set_get_yaw(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_raw_aux.h b/libraries/mavlink/include/pixhawk/mavlink_msg_raw_aux.h new file mode 100644 index 0000000000..0345153302 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_raw_aux.h @@ -0,0 +1,166 @@ +// MESSAGE RAW_AUX PACKING + +#define MAVLINK_MSG_ID_RAW_AUX 141 + +typedef struct __mavlink_raw_aux_t +{ + uint16_t adc1; ///< ADC1 (J405 ADC3, LPC2148 AD0.6) + uint16_t adc2; ///< ADC2 (J405 ADC5, LPC2148 AD0.2) + uint16_t adc3; ///< ADC3 (J405 ADC6, LPC2148 AD0.1) + uint16_t adc4; ///< ADC4 (J405 ADC7, LPC2148 AD1.3) + uint16_t vbat; ///< Battery voltage + int16_t temp; ///< Temperature (degrees celcius) + int32_t baro; ///< Barometric pressure (hecto Pascal) + +} mavlink_raw_aux_t; + + + +/** + * @brief Send a raw_aux message + * + * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6) + * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2) + * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1) + * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3) + * @param vbat Battery voltage + * @param temp Temperature (degrees celcius) + * @param baro Barometric pressure (hecto Pascal) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RAW_AUX; + + i += put_uint16_t_by_index(adc1, i, msg->payload); //ADC1 (J405 ADC3, LPC2148 AD0.6) + i += put_uint16_t_by_index(adc2, i, msg->payload); //ADC2 (J405 ADC5, LPC2148 AD0.2) + i += put_uint16_t_by_index(adc3, i, msg->payload); //ADC3 (J405 ADC6, LPC2148 AD0.1) + i += put_uint16_t_by_index(adc4, i, msg->payload); //ADC4 (J405 ADC7, LPC2148 AD1.3) + i += put_uint16_t_by_index(vbat, i, msg->payload); //Battery voltage + i += put_int16_t_by_index(temp, i, msg->payload); //Temperature (degrees celcius) + i += put_int32_t_by_index(baro, i, msg->payload); //Barometric pressure (hecto Pascal) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux) +{ + return mavlink_msg_raw_aux_pack(system_id, component_id, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) +{ + mavlink_message_t msg; + mavlink_msg_raw_aux_pack(mavlink_system.sysid, mavlink_system.compid, &msg, adc1, adc2, adc3, adc4, vbat, temp, baro); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RAW_AUX UNPACKING + +/** + * @brief Get field adc1 from raw_aux message + * + * @return ADC1 (J405 ADC3, LPC2148 AD0.6) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc1(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field adc2 from raw_aux message + * + * @return ADC2 (J405 ADC5, LPC2148 AD0.2) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc2(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field adc3 from raw_aux message + * + * @return ADC3 (J405 ADC6, LPC2148 AD0.1) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc3(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field adc4 from raw_aux message + * + * @return ADC4 (J405 ADC7, LPC2148 AD1.3) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc4(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field vbat from raw_aux message + * + * @return Battery voltage + */ +static inline uint16_t mavlink_msg_raw_aux_get_vbat(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field temp from raw_aux message + * + * @return Temperature (degrees celcius) + */ +static inline int16_t mavlink_msg_raw_aux_get_temp(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field baro from raw_aux message + * + * @return Barometric pressure (hecto Pascal) + */ +static inline int32_t mavlink_msg_raw_aux_get_baro(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[3]; + return (int32_t)r.i; +} + +static inline void mavlink_msg_raw_aux_decode(const mavlink_message_t* msg, mavlink_raw_aux_t* raw_aux) +{ + raw_aux->adc1 = mavlink_msg_raw_aux_get_adc1(msg); + raw_aux->adc2 = mavlink_msg_raw_aux_get_adc2(msg); + raw_aux->adc3 = mavlink_msg_raw_aux_get_adc3(msg); + raw_aux->adc4 = mavlink_msg_raw_aux_get_adc4(msg); + raw_aux->vbat = mavlink_msg_raw_aux_get_vbat(msg); + raw_aux->temp = mavlink_msg_raw_aux_get_temp(msg); + raw_aux->baro = mavlink_msg_raw_aux_get_baro(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_request_data_stream.h b/libraries/mavlink/include/pixhawk/mavlink_msg_request_data_stream.h new file mode 100644 index 0000000000..045dbc70b6 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_request_data_stream.h @@ -0,0 +1,118 @@ +// MESSAGE REQUEST_DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 81 + +typedef struct __mavlink_request_data_stream_t +{ + uint8_t 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 + uint16_t req_message_rate; ///< The requested interval between two messages of this type + uint8_t start_stop; ///< 1 to start sending, 0 to stop sending. + +} mavlink_request_data_stream_t; + + + +/** + * @brief Send a request_data_stream message + * + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested message type + * @param req_message_rate The requested interval between two messages of this type + * @param start_stop 1 to start sending, 0 to stop sending. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //The target requested to send the message stream. + i += put_uint8_t_by_index(target_component, i, msg->payload); //The target requested to send the message stream. + i += put_uint8_t_by_index(req_stream_id, i, msg->payload); //The ID of the requested message type + i += put_uint16_t_by_index(req_message_rate, i, msg->payload); //The requested interval between two messages of this type + i += put_uint8_t_by_index(start_stop, i, msg->payload); //1 to start sending, 0 to stop sending. + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) +{ + return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ + mavlink_message_t msg; + mavlink_msg_request_data_stream_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, req_stream_id, req_message_rate, start_stop); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE REQUEST_DATA_STREAM UNPACKING + +/** + * @brief Get field target_system from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field req_stream_id from request_data_stream message + * + * @return The ID of the requested message type + */ +static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field req_message_rate from request_data_stream message + * + * @return The requested interval between two messages of this type + */ +static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field start_stop from request_data_stream message + * + * @return 1 to start sending, 0 to stop sending. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; +} + +static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream) +{ + request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg); + request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg); + request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg); + request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg); + request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_request_dynamic_gyro_calibration.h b/libraries/mavlink/include/pixhawk/mavlink_msg_request_dynamic_gyro_calibration.h new file mode 100644 index 0000000000..8a8094b987 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_request_dynamic_gyro_calibration.h @@ -0,0 +1,123 @@ +// MESSAGE REQUEST_DYNAMIC_GYRO_CALIBRATION PACKING + +#define MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION 82 + +typedef struct __mavlink_request_dynamic_gyro_calibration_t +{ + uint8_t target_system; ///< The system which should auto-calibrate + uint8_t target_component; ///< The system component which should auto-calibrate + float mode; ///< The current ground-truth rpm + uint8_t axis; ///< The axis to calibrate: 0 roll, 1 pitch, 2 yaw + uint16_t time; ///< The time to average over in ms + +} mavlink_request_dynamic_gyro_calibration_t; + + + +/** + * @brief Send a request_dynamic_gyro_calibration message + * + * @param target_system The system which should auto-calibrate + * @param target_component The system component which should auto-calibrate + * @param mode The current ground-truth rpm + * @param axis The axis to calibrate: 0 roll, 1 pitch, 2 yaw + * @param time The time to average over in ms + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate + i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate + i += put_float_by_index(mode, i, msg->payload); //The current ground-truth rpm + i += put_uint8_t_by_index(axis, i, msg->payload); //The axis to calibrate: 0 roll, 1 pitch, 2 yaw + i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration) +{ + return mavlink_msg_request_dynamic_gyro_calibration_pack(system_id, component_id, msg, request_dynamic_gyro_calibration->target_system, request_dynamic_gyro_calibration->target_component, request_dynamic_gyro_calibration->mode, request_dynamic_gyro_calibration->axis, request_dynamic_gyro_calibration->time); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_dynamic_gyro_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time) +{ + mavlink_message_t msg; + mavlink_msg_request_dynamic_gyro_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, mode, axis, time); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE REQUEST_DYNAMIC_GYRO_CALIBRATION UNPACKING + +/** + * @brief Get field target_system from request_dynamic_gyro_calibration message + * + * @return The system which should auto-calibrate + */ +static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from request_dynamic_gyro_calibration message + * + * @return The system component which should auto-calibrate + */ +static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field mode from request_dynamic_gyro_calibration message + * + * @return The current ground-truth rpm + */ +static inline float mavlink_msg_request_dynamic_gyro_calibration_get_mode(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field axis from request_dynamic_gyro_calibration message + * + * @return The axis to calibrate: 0 roll, 1 pitch, 2 yaw + */ +static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_axis(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; +} + +/** + * @brief Get field time from request_dynamic_gyro_calibration message + * + * @return The time to average over in ms + */ +static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_get_time(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_request_dynamic_gyro_calibration_decode(const mavlink_message_t* msg, mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration) +{ + request_dynamic_gyro_calibration->target_system = mavlink_msg_request_dynamic_gyro_calibration_get_target_system(msg); + request_dynamic_gyro_calibration->target_component = mavlink_msg_request_dynamic_gyro_calibration_get_target_component(msg); + request_dynamic_gyro_calibration->mode = mavlink_msg_request_dynamic_gyro_calibration_get_mode(msg); + request_dynamic_gyro_calibration->axis = mavlink_msg_request_dynamic_gyro_calibration_get_axis(msg); + request_dynamic_gyro_calibration->time = mavlink_msg_request_dynamic_gyro_calibration_get_time(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_request_static_calibration.h b/libraries/mavlink/include/pixhawk/mavlink_msg_request_static_calibration.h new file mode 100644 index 0000000000..b97062e75b --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_request_static_calibration.h @@ -0,0 +1,90 @@ +// MESSAGE REQUEST_STATIC_CALIBRATION PACKING + +#define MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION 83 + +typedef struct __mavlink_request_static_calibration_t +{ + uint8_t target_system; ///< The system which should auto-calibrate + uint8_t target_component; ///< The system component which should auto-calibrate + uint16_t time; ///< The time to average over in ms + +} mavlink_request_static_calibration_t; + + + +/** + * @brief Send a request_static_calibration message + * + * @param target_system The system which should auto-calibrate + * @param target_component The system component which should auto-calibrate + * @param time The time to average over in ms + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_static_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t time) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION; + + i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate + i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate + i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_request_static_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_static_calibration_t* request_static_calibration) +{ + return mavlink_msg_request_static_calibration_pack(system_id, component_id, msg, request_static_calibration->target_system, request_static_calibration->target_component, request_static_calibration->time); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_static_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t time) +{ + mavlink_message_t msg; + mavlink_msg_request_static_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, time); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE REQUEST_STATIC_CALIBRATION UNPACKING + +/** + * @brief Get field target_system from request_static_calibration message + * + * @return The system which should auto-calibrate + */ +static inline uint8_t mavlink_msg_request_static_calibration_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from request_static_calibration message + * + * @return The system component which should auto-calibrate + */ +static inline uint8_t mavlink_msg_request_static_calibration_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field time from request_static_calibration message + * + * @return The time to average over in ms + */ +static inline uint16_t mavlink_msg_request_static_calibration_get_time(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_request_static_calibration_decode(const mavlink_message_t* msg, mavlink_request_static_calibration_t* request_static_calibration) +{ + request_static_calibration->target_system = mavlink_msg_request_static_calibration_get_target_system(msg); + request_static_calibration->target_component = mavlink_msg_request_static_calibration_get_target_component(msg); + request_static_calibration->time = mavlink_msg_request_static_calibration_get_time(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_set_altitude.h b/libraries/mavlink/include/pixhawk/mavlink_msg_set_altitude.h new file mode 100644 index 0000000000..27cae625ff --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_set_altitude.h @@ -0,0 +1,78 @@ +// MESSAGE SET_ALTITUDE PACKING + +#define MAVLINK_MSG_ID_SET_ALTITUDE 80 + +typedef struct __mavlink_set_altitude_t +{ + uint8_t target; ///< The system setting the altitude + uint32_t mode; ///< The new altitude in meters + +} mavlink_set_altitude_t; + + + +/** + * @brief Send a set_altitude message + * + * @param target The system setting the altitude + * @param mode The new altitude in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint32_t mode) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the altitude + i += put_uint32_t_by_index(mode, i, msg->payload); //The new altitude in meters + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_set_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_altitude_t* set_altitude) +{ + return mavlink_msg_set_altitude_pack(system_id, component_id, msg, set_altitude->target, set_altitude->mode); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_altitude_send(mavlink_channel_t chan, uint8_t target, uint32_t mode) +{ + mavlink_message_t msg; + mavlink_msg_set_altitude_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, mode); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SET_ALTITUDE UNPACKING + +/** + * @brief Get field target from set_altitude message + * + * @return The system setting the altitude + */ +static inline uint8_t mavlink_msg_set_altitude_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field mode from set_altitude message + * + * @return The new altitude in meters + */ +static inline uint32_t mavlink_msg_set_altitude_get_mode(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t))[3]; + return (uint32_t)r.i; +} + +static inline void mavlink_msg_set_altitude_decode(const mavlink_message_t* msg, mavlink_set_altitude_t* set_altitude) +{ + set_altitude->target = mavlink_msg_set_altitude_get_target(msg); + set_altitude->mode = mavlink_msg_set_altitude_get_mode(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_set_cam_shutter.h b/libraries/mavlink/include/pixhawk/mavlink_msg_set_cam_shutter.h new file mode 100644 index 0000000000..f9ef3f125b --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_set_cam_shutter.h @@ -0,0 +1,140 @@ +// MESSAGE SET_CAM_SHUTTER PACKING + +#define MAVLINK_MSG_ID_SET_CAM_SHUTTER 100 + +typedef struct __mavlink_set_cam_shutter_t +{ + uint8_t cam_no; ///< Camera id + uint8_t cam_mode; ///< Camera mode: 0 = auto, 1 = manual + uint8_t trigger_pin; ///< Trigger pin, 0-3 for PtGrey FireFly + uint16_t interval; ///< Shutter interval, in microseconds + uint16_t exposure; ///< Exposure time, in microseconds + float gain; ///< Camera gain + +} mavlink_set_cam_shutter_t; + + + +/** + * @brief Send a set_cam_shutter message + * + * @param cam_no Camera id + * @param cam_mode Camera mode: 0 = auto, 1 = manual + * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly + * @param interval Shutter interval, in microseconds + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; + + i += put_uint8_t_by_index(cam_no, i, msg->payload); //Camera id + i += put_uint8_t_by_index(cam_mode, i, msg->payload); //Camera mode: 0 = auto, 1 = manual + i += put_uint8_t_by_index(trigger_pin, i, msg->payload); //Trigger pin, 0-3 for PtGrey FireFly + i += put_uint16_t_by_index(interval, i, msg->payload); //Shutter interval, in microseconds + i += put_uint16_t_by_index(exposure, i, msg->payload); //Exposure time, in microseconds + i += put_float_by_index(gain, i, msg->payload); //Camera gain + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter) +{ + return mavlink_msg_set_cam_shutter_pack(system_id, component_id, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) +{ + mavlink_message_t msg; + mavlink_msg_set_cam_shutter_pack(mavlink_system.sysid, mavlink_system.compid, &msg, cam_no, cam_mode, trigger_pin, interval, exposure, gain); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SET_CAM_SHUTTER UNPACKING + +/** + * @brief Get field cam_no from set_cam_shutter message + * + * @return Camera id + */ +static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_no(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field cam_mode from set_cam_shutter message + * + * @return Camera mode: 0 = auto, 1 = manual + */ +static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field trigger_pin from set_cam_shutter message + * + * @return Trigger pin, 0-3 for PtGrey FireFly + */ +static inline uint8_t mavlink_msg_set_cam_shutter_get_trigger_pin(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field interval from set_cam_shutter message + * + * @return Shutter interval, in microseconds + */ +static inline uint16_t mavlink_msg_set_cam_shutter_get_interval(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field exposure from set_cam_shutter message + * + * @return Exposure time, in microseconds + */ +static inline uint16_t mavlink_msg_set_cam_shutter_get_exposure(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field gain from set_cam_shutter message + * + * @return Camera gain + */ +static inline float mavlink_msg_set_cam_shutter_get_gain(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_set_cam_shutter_decode(const mavlink_message_t* msg, mavlink_set_cam_shutter_t* set_cam_shutter) +{ + set_cam_shutter->cam_no = mavlink_msg_set_cam_shutter_get_cam_no(msg); + set_cam_shutter->cam_mode = mavlink_msg_set_cam_shutter_get_cam_mode(msg); + set_cam_shutter->trigger_pin = mavlink_msg_set_cam_shutter_get_trigger_pin(msg); + set_cam_shutter->interval = mavlink_msg_set_cam_shutter_get_interval(msg); + set_cam_shutter->exposure = mavlink_msg_set_cam_shutter_get_exposure(msg); + set_cam_shutter->gain = mavlink_msg_set_cam_shutter_get_gain(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h b/libraries/mavlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h new file mode 100644 index 0000000000..0857d653d6 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h @@ -0,0 +1,182 @@ +// MESSAGE VICON_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 112 + +typedef struct __mavlink_vicon_position_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float 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 + +} mavlink_vicon_position_estimate_t; + + + +/** + * @brief Send a vicon_position_estimate message + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; + + i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (milliseconds) + i += put_float_by_index(x, i, msg->payload); //Global X position + i += put_float_by_index(y, i, msg->payload); //Global Y position + i += put_float_by_index(z, i, msg->payload); //Global Z position + i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad + i += put_float_by_index(yaw, i, msg->payload); //Yaw angle in rad + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ + return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_vicon_position_estimate_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, x, y, z, roll, pitch, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE VICON_POSITION_ESTIMATE UNPACKING + +/** + * @brief Get field usec from vicon_position_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field x from vicon_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from vicon_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from vicon_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field roll from vicon_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from vicon_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from vicon_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ + vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg); + vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg); + vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg); + vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg); + vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg); + vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg); + vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_vision_position_estimate.h b/libraries/mavlink/include/pixhawk/mavlink_msg_vision_position_estimate.h new file mode 100644 index 0000000000..623027706f --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_vision_position_estimate.h @@ -0,0 +1,182 @@ +// MESSAGE VISION_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 111 + +typedef struct __mavlink_vision_position_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float 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 + +} mavlink_vision_position_estimate_t; + + + +/** + * @brief Send a vision_position_estimate message + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; + + i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (milliseconds) + i += put_float_by_index(x, i, msg->payload); //Global X position + i += put_float_by_index(y, i, msg->payload); //Global Y position + i += put_float_by_index(z, i, msg->payload); //Global Z position + i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad + i += put_float_by_index(yaw, i, msg->payload); //Yaw angle in rad + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) +{ + return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_vision_position_estimate_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, x, y, z, roll, pitch, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE VISION_POSITION_ESTIMATE UNPACKING + +/** + * @brief Get field usec from vision_position_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field x from vision_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from vision_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from vision_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field roll from vision_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from vision_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from vision_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate) +{ + vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg); + vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg); + vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg); + vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg); + vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg); + vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg); + vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_command.h b/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_command.h new file mode 100644 index 0000000000..e09fe7d04f --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_command.h @@ -0,0 +1,107 @@ +// MESSAGE WATCHDOG_COMMAND PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_COMMAND 153 + +typedef struct __mavlink_watchdog_command_t +{ + uint8_t target_system_id; ///< Target system ID + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_id; ///< Process ID + uint8_t command_id; ///< Command ID + +} mavlink_watchdog_command_t; + + + +/** + * @brief Send a watchdog_command message + * + * @param target_system_id Target system ID + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param command_id Command ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; + + i += put_uint8_t_by_index(target_system_id, i, msg->payload); //Target system ID + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID + i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID + i += put_uint8_t_by_index(command_id, i, msg->payload); //Command ID + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command) +{ + return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) +{ + mavlink_message_t msg; + mavlink_msg_watchdog_command_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system_id, watchdog_id, process_id, command_id); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WATCHDOG_COMMAND UNPACKING + +/** + * @brief Get field target_system_id from watchdog_command message + * + * @return Target system ID + */ +static inline uint8_t mavlink_msg_watchdog_command_get_target_system_id(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field watchdog_id from watchdog_command message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_command_get_watchdog_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field process_id from watchdog_command message + * + * @return Process ID + */ +static inline uint16_t mavlink_msg_watchdog_command_get_process_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field command_id from watchdog_command message + * + * @return Command ID + */ +static inline uint8_t mavlink_msg_watchdog_command_get_command_id(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; +} + +static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* msg, mavlink_watchdog_command_t* watchdog_command) +{ + watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg); + watchdog_command->watchdog_id = mavlink_msg_watchdog_command_get_watchdog_id(msg); + watchdog_command->process_id = mavlink_msg_watchdog_command_get_process_id(msg); + watchdog_command->command_id = mavlink_msg_watchdog_command_get_command_id(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h b/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h new file mode 100644 index 0000000000..1b222eac42 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h @@ -0,0 +1,79 @@ +// MESSAGE WATCHDOG_HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT 150 + +typedef struct __mavlink_watchdog_heartbeat_t +{ + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_count; ///< Number of processes + +} mavlink_watchdog_heartbeat_t; + + + +/** + * @brief Send a watchdog_heartbeat message + * + * @param watchdog_id Watchdog ID + * @param process_count Number of processes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_count) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; + + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID + i += put_uint16_t_by_index(process_count, i, msg->payload); //Number of processes + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat) +{ + return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count) +{ + mavlink_message_t msg; + mavlink_msg_watchdog_heartbeat_pack(mavlink_system.sysid, mavlink_system.compid, &msg, watchdog_id, process_count); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WATCHDOG_HEARTBEAT UNPACKING + +/** + * @brief Get field watchdog_id from watchdog_heartbeat message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_get_watchdog_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field process_count from watchdog_heartbeat message + * + * @return Number of processes + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_get_process_count(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_watchdog_heartbeat_decode(const mavlink_message_t* msg, mavlink_watchdog_heartbeat_t* watchdog_heartbeat) +{ + watchdog_heartbeat->watchdog_id = mavlink_msg_watchdog_heartbeat_get_watchdog_id(msg); + watchdog_heartbeat->process_count = mavlink_msg_watchdog_heartbeat_get_process_count(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_process_info.h b/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_process_info.h new file mode 100644 index 0000000000..20246e40d3 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_process_info.h @@ -0,0 +1,132 @@ +// MESSAGE WATCHDOG_PROCESS_INFO PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO 151 + +typedef struct __mavlink_watchdog_process_info_t +{ + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_id; ///< Process ID + int8_t name[100]; ///< Process name + int8_t arguments[147]; ///< Process arguments + int32_t timeout; ///< Timeout (seconds) + +} mavlink_watchdog_process_info_t; + +#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_NAME_LEN 100 +#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_ARGUMENTS_LEN 147 + + +/** + * @brief Send a watchdog_process_info message + * + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param name Process name + * @param arguments Process arguments + * @param timeout Timeout (seconds) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; + + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID + i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID + i += put_array_by_index(name, 100, i, msg->payload); //Process name + i += put_array_by_index(arguments, 147, i, msg->payload); //Process arguments + i += put_int32_t_by_index(timeout, i, msg->payload); //Timeout (seconds) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info) +{ + return mavlink_msg_watchdog_process_info_pack(system_id, component_id, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout) +{ + mavlink_message_t msg; + mavlink_msg_watchdog_process_info_pack(mavlink_system.sysid, mavlink_system.compid, &msg, watchdog_id, process_id, name, arguments, timeout); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WATCHDOG_PROCESS_INFO UNPACKING + +/** + * @brief Get field watchdog_id from watchdog_process_info message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_watchdog_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field process_id from watchdog_process_info message + * + * @return Process ID + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_process_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field name from watchdog_process_info message + * + * @return Process name + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint16_t)+sizeof(uint16_t), 100); + return 100; +} + +/** + * @brief Get field arguments from watchdog_process_info message + * + * @return Process arguments + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100, 147); + return 147; +} + +/** + * @brief Get field timeout from watchdog_process_info message + * + * @return Timeout (seconds) + */ +static inline int32_t mavlink_msg_watchdog_process_info_get_timeout(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[3]; + return (int32_t)r.i; +} + +static inline void mavlink_msg_watchdog_process_info_decode(const mavlink_message_t* msg, mavlink_watchdog_process_info_t* watchdog_process_info) +{ + watchdog_process_info->watchdog_id = mavlink_msg_watchdog_process_info_get_watchdog_id(msg); + watchdog_process_info->process_id = mavlink_msg_watchdog_process_info_get_process_id(msg); + mavlink_msg_watchdog_process_info_get_name(msg, watchdog_process_info->name); + mavlink_msg_watchdog_process_info_get_arguments(msg, watchdog_process_info->arguments); + watchdog_process_info->timeout = mavlink_msg_watchdog_process_info_get_timeout(msg); +} diff --git a/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_process_status.h b/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_process_status.h new file mode 100644 index 0000000000..fd3cea90a9 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/mavlink_msg_watchdog_process_status.h @@ -0,0 +1,143 @@ +// MESSAGE WATCHDOG_PROCESS_STATUS PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS 152 + +typedef struct __mavlink_watchdog_process_status_t +{ + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_id; ///< Process ID + uint8_t state; ///< Is running / finished / suspended / crashed + uint8_t muted; ///< Is muted + int32_t pid; ///< PID + uint16_t crashes; ///< Number of crashes + +} mavlink_watchdog_process_status_t; + + + +/** + * @brief Send a watchdog_process_status message + * + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param state Is running / finished / suspended / crashed + * @param muted Is muted + * @param pid PID + * @param crashes Number of crashes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; + + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID + i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID + i += put_uint8_t_by_index(state, i, msg->payload); //Is running / finished / suspended / crashed + i += put_uint8_t_by_index(muted, i, msg->payload); //Is muted + i += put_int32_t_by_index(pid, i, msg->payload); //PID + i += put_uint16_t_by_index(crashes, i, msg->payload); //Number of crashes + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status) +{ + return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) +{ + mavlink_message_t msg; + mavlink_msg_watchdog_process_status_pack(mavlink_system.sysid, mavlink_system.compid, &msg, watchdog_id, process_id, state, muted, pid, crashes); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WATCHDOG_PROCESS_STATUS UNPACKING + +/** + * @brief Get field watchdog_id from watchdog_process_status message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field process_id from watchdog_process_status message + * + * @return Process ID + */ +static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field state from watchdog_process_status message + * + * @return Is running / finished / suspended / crashed + */ +static inline uint8_t mavlink_msg_watchdog_process_status_get_state(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0]; +} + +/** + * @brief Get field muted from watchdog_process_status message + * + * @return Is muted + */ +static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field pid from watchdog_process_status message + * + * @return PID + */ +static inline int32_t mavlink_msg_watchdog_process_status_get_pid(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field crashes from watchdog_process_status message + * + * @return Number of crashes + */ +static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_message_t* msg, mavlink_watchdog_process_status_t* watchdog_process_status) +{ + watchdog_process_status->watchdog_id = mavlink_msg_watchdog_process_status_get_watchdog_id(msg); + watchdog_process_status->process_id = mavlink_msg_watchdog_process_status_get_process_id(msg); + watchdog_process_status->state = mavlink_msg_watchdog_process_status_get_state(msg); + watchdog_process_status->muted = mavlink_msg_watchdog_process_status_get_muted(msg); + watchdog_process_status->pid = mavlink_msg_watchdog_process_status_get_pid(msg); + watchdog_process_status->crashes = mavlink_msg_watchdog_process_status_get_crashes(msg); +} diff --git a/libraries/mavlink/include/pixhawk/pixhawk.h b/libraries/mavlink/include/pixhawk/pixhawk.h new file mode 100644 index 0000000000..ad009251c2 --- /dev/null +++ b/libraries/mavlink/include/pixhawk/pixhawk.h @@ -0,0 +1,48 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Sunday, October 24 2010, 08:46 UTC + */ +#ifndef PIXHAWK_H +#define PIXHAWK_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_PIXHAWK + + +#include "../common/common.h" +#include "./mavlink_msg_set_altitude.h" +#include "./mavlink_msg_request_data_stream.h" +#include "./mavlink_msg_request_dynamic_gyro_calibration.h" +#include "./mavlink_msg_request_static_calibration.h" +#include "./mavlink_msg_manual_control.h" +#include "./mavlink_msg_attitude_control.h" +#include "./mavlink_msg_debug_vect.h" +#include "./mavlink_msg_set_cam_shutter.h" +#include "./mavlink_msg_image_triggered.h" +#include "./mavlink_msg_image_trigger_control.h" +#include "./mavlink_msg_image_available.h" +#include "./mavlink_msg_vision_position_estimate.h" +#include "./mavlink_msg_vicon_position_estimate.h" +#include "./mavlink_msg_position_control_setpoint_set.h" +#include "./mavlink_msg_position_control_offset_set.h" +#include "./mavlink_msg_position_control_setpoint.h" +#include "./mavlink_msg_marker.h" +#include "./mavlink_msg_raw_aux.h" +#include "./mavlink_msg_aux_status.h" +#include "./mavlink_msg_control_status.h" +#include "./mavlink_msg_watchdog_heartbeat.h" +#include "./mavlink_msg_watchdog_process_info.h" +#include "./mavlink_msg_watchdog_process_status.h" +#include "./mavlink_msg_watchdog_command.h" +#include "./mavlink_msg_pattern_detected.h" +#ifdef __cplusplus +} +#endif +#endif diff --git a/libraries/mavlink/include/protocol.h b/libraries/mavlink/include/protocol.h new file mode 100644 index 0000000000..e1e0b486a2 --- /dev/null +++ b/libraries/mavlink/include/protocol.h @@ -0,0 +1,856 @@ +#ifndef _MAVLINK_PROTOCOL_H_ +#define _MAVLINK_PROTOCOL_H_ + +#include "string.h" +#include "checksum.h" + +#include "mavlink_types.h" + +/** + * @brief Finalize a MAVLink message + * + * 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. + * + * @param msg Message to finalize + * @param system_id Id of the sending (this) system, 1-127 + * @param length Message length, usually just the counter incremented while packing the message + */ +static inline uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint16_t length) +{ + // This code part is the same for all messages; + static uint8_t seq = 0; + uint16_t checksum; + msg->len = length; + msg->sysid = system_id; + msg->compid = component_id; + // One sequence number per component + msg->seq = seq++; + + checksum = crc_calculate((uint8_t*)((void*)msg), length + MAVLINK_CORE_HEADER_LEN); + msg->ck_a = (uint8_t)(checksum & 0xFF); ///< High byte + msg->ck_b = (uint8_t)(checksum >> 8); ///< Low byte + + return length + MAVLINK_NUM_NON_STX_PAYLOAD_BYTES; +} + +/** + * @brief Pack a message to send it over a serial byte stream + */ +static inline uint16_t mavlink_msg_to_send_buffer(uint8_t* buffer, const mavlink_message_t* msg) +{ + *(buffer+0) = MAVLINK_STX; ///< Start transmit + memcpy((buffer+1), msg, msg->len + MAVLINK_CORE_HEADER_LEN); ///< Core header plus payload + *(buffer + msg->len + MAVLINK_CORE_HEADER_LEN + 1) = msg->ck_a; + *(buffer + msg->len + MAVLINK_CORE_HEADER_LEN + 2) = msg->ck_b; + return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; + return 0; +} + +/** + * @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; +} + +union checksum_ { + uint16_t s; + uint8_t c[2]; +}; + +union __mavlink_bitfield { + uint8_t uint8; + int8_t int8; + uint16_t uint16; + int16_t int16; + uint32_t uint32; + int32_t int32; +}; + + +static inline void mavlink_start_checksum(mavlink_message_t* msg) +{ + union checksum_ ck; + crc_init(&(ck.s)); + msg->ck_a = ck.c[0]; + msg->ck_b = ck.c[1]; +} + +static inline void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) +{ + union checksum_ ck; + ck.c[0] = msg->ck_a; + ck.c[1] = msg->ck_b; + crc_accumulate(c, &(ck.s)); + msg->ck_a = ck.c[0]; + msg->ck_b = ck.c[1]; +} + + +/** + * @brief Initialize the communication stack + * + * This function has to be called before using commParseBuffer() to initialize the different status registers. + * + * @return Will initialize the different buffers and status registers. + */ +static void mavlink_parse_state_initialize(mavlink_status_t* initStatus) +{ + if ((initStatus->parse_state <= MAVLINK_PARSE_STATE_UNINIT) || (initStatus->parse_state > MAVLINK_PARSE_STATE_GOT_CRC1)) + { + initStatus->ck_a = 0; + initStatus->ck_b = 0; + initStatus->msg_received = 0; + initStatus->buffer_overrun = 0; + initStatus->parse_error = 0; + initStatus->parse_state = MAVLINK_PARSE_STATE_UNINIT; + initStatus->packet_idx = 0; + initStatus->packet_rx_drop_count = 0; + initStatus->packet_rx_success_count = 0; + } +} + +/** + * 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 + */ +static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ +#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH]; + static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH]; +#else + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB]; + static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB]; +#endif + // Initializes only once, values keep unchanged after first initialization + mavlink_parse_state_initialize(&m_mavlink_status[chan]); + + mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message + mavlink_status_t* status = &m_mavlink_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; + mavlink_start_checksum(rxmsg); + } + break; + + case MAVLINK_PARSE_STATE_GOT_STX: + if (status->msg_received) + { + 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: + 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: + rxmsg->payload[status->packet_idx++] = 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 (c != rxmsg->ck_a) + { + // 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; + mavlink_start_checksum(rxmsg); + } + } + else + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; + } + break; + + case MAVLINK_PARSE_STATE_GOT_CRC1: + if (c != rxmsg->ck_b) + {// 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; + mavlink_start_checksum(rxmsg); + } + } + else + { + // Successfully got message + status->msg_received = 1; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + 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_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_mavlink_status->current_seq = status->current_seq+1; + r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; + r_mavlink_status->packet_rx_drop_count = status->parse_error; + 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. 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 + */ + +#define MAVLINK_PACKET_START_CANDIDATES 50 +/* +static inline uint8_t mavlink_parse_char_new(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH]; + static uint8_t m_msgbuf[MAVLINK_COMM_NB_HIGH][MAVLINK_MAX_PACKET_LEN * 2]; + static uint8_t m_msgbuf_index[MAVLINK_COMM_NB_HIGH]; + static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH]; + static uint8_t m_packet_start[MAVLINK_COMM_NB_HIGH][MAVLINK_PACKET_START_CANDIDATES]; + static uint8_t m_packet_start_index_read[MAVLINK_COMM_NB_HIGH]; + static uint8_t m_packet_start_index_write[MAVLINK_COMM_NB_HIGH]; + #else + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB]; + static uint8_t m_msgbuf[MAVLINK_COMM_NB][MAVLINK_MAX_PACKET_LEN * 2]; + static uint8_t m_msgbuf_index[MAVLINK_COMM_NB]; + static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB]; + static uint8_t m_packet_start[MAVLINK_COMM_NB][MAVLINK_PACKET_START_CANDIDATES]; + static uint8_t m_packet_start_index_read[MAVLINK_COMM_NB]; + static uint8_t m_packet_start_index_write[MAVLINK_COMM_NB]; + #endif + + // Set a packet start candidate index if sign is start sign + if (c == MAVLINK_STX) + { + m_packet_start[chan][++(m_packet_start_index_write[chan]) % MAVLINK_PACKET_START_CANDIDATES] = m_msgbuf_index[chan]; + } + + // Parse normally, if a CRC mismatch occurs retry with the next packet index +} +//#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) +// static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH]; +// static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH]; +//#else +// static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB]; +// static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB]; +//#endif +//// Initializes only once, values keep unchanged after first initialization +// mavlink_parse_state_initialize(&m_mavlink_status[chan]); +// +//mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message +//mavlink_status_t* status = &m_mavlink_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; +// mavlink_start_checksum(rxmsg); +// } +// break; +// +//case MAVLINK_PARSE_STATE_GOT_STX: +// if (status->msg_received) +// { +// 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: +// 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: +// rxmsg->payload[status->packet_idx++] = 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 (c != rxmsg->ck_a) +// { +// // Check first checksum byte +// status->parse_error++; +// status->msg_received = 0; +// status->parse_state = MAVLINK_PARSE_STATE_IDLE; +// } +// else +// { +// status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; +// } +// break; +// +//case MAVLINK_PARSE_STATE_GOT_CRC1: +// if (c != rxmsg->ck_b) +// {// Check second checksum byte +// status->parse_error++; +// status->msg_received = 0; +// status->parse_state = MAVLINK_PARSE_STATE_IDLE; +// } +// else +// { +// // Successfully got message +// status->msg_received = 1; +// status->parse_state = MAVLINK_PARSE_STATE_IDLE; +// 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_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_mavlink_status->current_seq = status->current_seq+1; +r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; +r_mavlink_status->packet_rx_drop_count = status->parse_error; +return status->msg_received; +} + */ + + +typedef union __generic_16bit +{ + uint8_t b[2]; + int16_t s; +} generic_16bit; + +typedef union __generic_32bit +{ + uint8_t b[4]; + float f; + int32_t i; + int16_t s; +} generic_32bit; + +typedef union __generic_64bit +{ + uint8_t b[8]; + int64_t ll; ///< Long long (64 bit) +} generic_64bit; + +/** + * @brief Place an unsigned byte into the buffer + * + * @param b the byte to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_uint8_t_by_index(uint8_t b, uint8_t bindex, uint8_t* buffer) +{ + *(buffer + bindex) = b; + return sizeof(b); +} + +/** + * @brief Place a signed byte into the buffer + * + * @param b the byte to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_int8_t_by_index(int8_t b, int8_t bindex, uint8_t* buffer) +{ + *(buffer + bindex) = (uint8_t)b; + return sizeof(b); +} + +/** + * @brief Place two unsigned bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_uint16_t_by_index(uint16_t b, const uint8_t bindex, uint8_t* buffer) +{ + buffer[bindex] = (b>>8)&0xff; + buffer[bindex+1] = (b & 0xff); + return sizeof(b); +} + +/** + * @brief Place two signed bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_int16_t_by_index(int16_t b, uint8_t bindex, uint8_t* buffer) +{ + return put_uint16_t_by_index(b, bindex, buffer); +} + +/** + * @brief Place four unsigned bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_uint32_t_by_index(uint32_t b, const uint8_t bindex, uint8_t* buffer) +{ + buffer[bindex] = (b>>24)&0xff; + buffer[bindex+1] = (b>>16)&0xff; + buffer[bindex+2] = (b>>8)&0xff; + buffer[bindex+3] = (b & 0xff); + return sizeof(b); +} + +/** + * @brief Place four signed bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_int32_t_by_index(int32_t b, uint8_t bindex, uint8_t* buffer) +{ + buffer[bindex] = (b>>24)&0xff; + buffer[bindex+1] = (b>>16)&0xff; + buffer[bindex+2] = (b>>8)&0xff; + buffer[bindex+3] = (b & 0xff); + return sizeof(b); +} + +/** + * @brief Place four unsigned bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_uint64_t_by_index(uint64_t b, const uint8_t bindex, uint8_t* buffer) +{ + buffer[bindex] = (b>>56)&0xff; + buffer[bindex+1] = (b>>48)&0xff; + buffer[bindex+2] = (b>>40)&0xff; + buffer[bindex+3] = (b>>32)&0xff; + buffer[bindex+4] = (b>>24)&0xff; + buffer[bindex+5] = (b>>16)&0xff; + buffer[bindex+6] = (b>>8)&0xff; + buffer[bindex+7] = (b & 0xff); + return sizeof(b); +} + +/** + * @brief Place four signed bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_int64_t_by_index(int64_t b, uint8_t bindex, uint8_t* buffer) +{ + return put_uint64_t_by_index(b, bindex, buffer); +} + +/** + * @brief Place a float into the buffer + * + * @param b the float to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_float_by_index(float b, uint8_t bindex, uint8_t* buffer) +{ + generic_32bit g; + g.f = b; + return put_int32_t_by_index(g.i, bindex, buffer); +} + +/** + * @brief Place an array into the buffer + * + * @param b the array to add + * @param length size of the array (for strings: length WITH '\0' char) + * @param bindex the position in the packet + * @param buffer packet buffer + * @return new position of the last used byte in the buffer + */ +static inline uint8_t put_array_by_index(const int8_t* b, uint8_t length, uint8_t bindex, uint8_t* buffer) +{ + memcpy(buffer+bindex, b, length); + return length; +} + +/** + * @brief Place a string into the buffer + * + * @param b the string to add + * @param maxlength size of the array (for strings: length WITHOUT '\0' char) + * @param bindex the position in the packet + * @param buffer packet buffer + * @return new position of the last used byte in the buffer + */ +static inline uint8_t put_string_by_index(const char* b, uint8_t maxlength, uint8_t bindex, uint8_t* buffer) +{ + uint16_t length = 0; + // Copy string into buffer, ensuring not to exceed the buffer size + int i; + for (i = 1; i < maxlength; i++) + { + length++; + // String characters + if (i < (maxlength - 1)) + { + buffer[bindex+i] = b[i]; + // Stop at null character + if (b[i] == '\0') + { + break; + } + } + // Enforce null termination at end of buffer + else if (i == (maxlength - 1)) + { + buffer[i] = '\0'; + } + } + // Write length into first field + put_uint8_t_by_index(length, bindex, buffer); + return length; +} + +/** + * @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 + */ +static inline 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 + generic_32bit bin; + generic_32bit bout; + uint8_t i_bit_index, i_byte_index, curr_bits_n; + 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]; + + // 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 <= (8 - i_bit_index)) + { + // Enough space + curr_bits_n = 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) & bout.i); + + // 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 a similar function + +/* + +#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); + } +} + */ + + +static inline void mavlink_send_uart(mavlink_channel_t chan, mavlink_message_t* msg) +{ + // ARM7 MCU board implementation + // Create pointer on message struct + // Send STX + comm_send_ch(chan, MAVLINK_STX); + comm_send_ch(chan, msg->len); + comm_send_ch(chan, msg->seq); + comm_send_ch(chan, msg->sysid); + comm_send_ch(chan, msg->compid); + comm_send_ch(chan, msg->msgid); + for(uint16_t i = 0; i < msg->len; i++) + { + comm_send_ch(chan, msg->payload[i]); + } + comm_send_ch(chan, msg->ck_a); + comm_send_ch(chan, msg->ck_b); +} +#endif + +#endif /* _MAVLINK_PROTOCOL_H_ */ diff --git a/libraries/mavlink/include/slugs/mavlink.h b/libraries/mavlink/include/slugs/mavlink.h new file mode 100644 index 0000000000..5fb3c93693 --- /dev/null +++ b/libraries/mavlink/include/slugs/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Sunday, October 24 2010, 08:47 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "slugs.h" + +#endif diff --git a/libraries/mavlink/include/slugs/mavlink_msg_air_data.h b/libraries/mavlink/include/slugs/mavlink_msg_air_data.h new file mode 100644 index 0000000000..24517be7b1 --- /dev/null +++ b/libraries/mavlink/include/slugs/mavlink_msg_air_data.h @@ -0,0 +1,114 @@ +// MESSAGE AIR_DATA PACKING + +#define MAVLINK_MSG_ID_AIR_DATA 191 + +typedef struct __mavlink_air_data_t +{ + uint8_t target; ///< The system reporting the air data + float dynamicPressure; ///< Dynamic pressure (Pa) + float staticPressure; ///< Static pressure (Pa) + uint16_t temperature; ///< Board temperature + +} mavlink_air_data_t; + + + +/** + * @brief Send a air_data message + * + * @param target The system reporting the air data + * @param dynamicPressure Dynamic pressure (Pa) + * @param staticPressure Static pressure (Pa) + * @param temperature Board temperature + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_air_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float dynamicPressure, float staticPressure, uint16_t temperature) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_AIR_DATA; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the air data + i += put_float_by_index(dynamicPressure, i, msg->payload); //Dynamic pressure (Pa) + i += put_float_by_index(staticPressure, i, msg->payload); //Static pressure (Pa) + i += put_uint16_t_by_index(temperature, i, msg->payload); //Board temperature + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_air_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_air_data_t* air_data) +{ + return mavlink_msg_air_data_pack(system_id, component_id, msg, air_data->target, air_data->dynamicPressure, air_data->staticPressure, air_data->temperature); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, uint8_t target, float dynamicPressure, float staticPressure, uint16_t temperature) +{ + mavlink_message_t msg; + mavlink_msg_air_data_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, dynamicPressure, staticPressure, temperature); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE AIR_DATA UNPACKING + +/** + * @brief Get field target from air_data message + * + * @return The system reporting the air data + */ +static inline uint8_t mavlink_msg_air_data_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field dynamicPressure from air_data message + * + * @return Dynamic pressure (Pa) + */ +static inline float mavlink_msg_air_data_get_dynamicPressure(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field staticPressure from air_data message + * + * @return Static pressure (Pa) + */ +static inline float mavlink_msg_air_data_get_staticPressure(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field temperature from air_data message + * + * @return Board temperature + */ +static inline uint16_t mavlink_msg_air_data_get_temperature(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_air_data_decode(const mavlink_message_t* msg, mavlink_air_data_t* air_data) +{ + air_data->target = mavlink_msg_air_data_get_target(msg); + air_data->dynamicPressure = mavlink_msg_air_data_get_dynamicPressure(msg); + air_data->staticPressure = mavlink_msg_air_data_get_staticPressure(msg); + air_data->temperature = mavlink_msg_air_data_get_temperature(msg); +} diff --git a/libraries/mavlink/include/slugs/mavlink_msg_cpu_load.h b/libraries/mavlink/include/slugs/mavlink_msg_cpu_load.h new file mode 100644 index 0000000000..2b20bf228f --- /dev/null +++ b/libraries/mavlink/include/slugs/mavlink_msg_cpu_load.h @@ -0,0 +1,104 @@ +// MESSAGE CPU_LOAD PACKING + +#define MAVLINK_MSG_ID_CPU_LOAD 190 + +typedef struct __mavlink_cpu_load_t +{ + uint8_t target; ///< The system reporting the CPU load + uint8_t sensLoad; ///< Sensor DSC Load + uint8_t ctrlLoad; ///< Control DSC Load + uint16_t batVolt; ///< Battery Voltage in millivolts + +} mavlink_cpu_load_t; + + + +/** + * @brief Send a cpu_load message + * + * @param target The system reporting the CPU load + * @param sensLoad Sensor DSC Load + * @param ctrlLoad Control DSC Load + * @param batVolt Battery Voltage in millivolts + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_cpu_load_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_CPU_LOAD; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the CPU load + i += put_uint8_t_by_index(sensLoad, i, msg->payload); //Sensor DSC Load + i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); //Control DSC Load + i += put_uint16_t_by_index(batVolt, i, msg->payload); //Battery Voltage in millivolts + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_cpu_load_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cpu_load_t* cpu_load) +{ + return mavlink_msg_cpu_load_pack(system_id, component_id, msg, cpu_load->target, cpu_load->sensLoad, cpu_load->ctrlLoad, cpu_load->batVolt); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_cpu_load_send(mavlink_channel_t chan, uint8_t target, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt) +{ + mavlink_message_t msg; + mavlink_msg_cpu_load_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, sensLoad, ctrlLoad, batVolt); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE CPU_LOAD UNPACKING + +/** + * @brief Get field target from cpu_load message + * + * @return The system reporting the CPU load + */ +static inline uint8_t mavlink_msg_cpu_load_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field sensLoad from cpu_load message + * + * @return Sensor DSC Load + */ +static inline uint8_t mavlink_msg_cpu_load_get_sensLoad(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field ctrlLoad from cpu_load message + * + * @return Control DSC Load + */ +static inline uint8_t mavlink_msg_cpu_load_get_ctrlLoad(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field batVolt from cpu_load message + * + * @return Battery Voltage in millivolts + */ +static inline uint16_t mavlink_msg_cpu_load_get_batVolt(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_cpu_load_decode(const mavlink_message_t* msg, mavlink_cpu_load_t* cpu_load) +{ + cpu_load->target = mavlink_msg_cpu_load_get_target(msg); + cpu_load->sensLoad = mavlink_msg_cpu_load_get_sensLoad(msg); + cpu_load->ctrlLoad = mavlink_msg_cpu_load_get_ctrlLoad(msg); + cpu_load->batVolt = mavlink_msg_cpu_load_get_batVolt(msg); +} diff --git a/libraries/mavlink/include/slugs/mavlink_msg_diagnostic.h b/libraries/mavlink/include/slugs/mavlink_msg_diagnostic.h new file mode 100644 index 0000000000..73a2acf507 --- /dev/null +++ b/libraries/mavlink/include/slugs/mavlink_msg_diagnostic.h @@ -0,0 +1,167 @@ +// MESSAGE DIAGNOSTIC PACKING + +#define MAVLINK_MSG_ID_DIAGNOSTIC 193 + +typedef struct __mavlink_diagnostic_t +{ + uint8_t target; ///< The system reporting the diagnostic + float diagFl1; ///< Diagnostic float 1 + float diagFl2; ///< Diagnostic float 2 + float diagFl3; ///< Diagnostic float 3 + int16_t diagSh1; ///< Diagnostic short 1 + int16_t diagSh2; ///< Diagnostic short 2 + int16_t diagSh3; ///< Diagnostic short 3 + +} mavlink_diagnostic_t; + + + +/** + * @brief Send a diagnostic message + * + * @param target The system reporting the diagnostic + * @param diagFl1 Diagnostic float 1 + * @param diagFl2 Diagnostic float 2 + * @param diagFl3 Diagnostic float 3 + * @param diagSh1 Diagnostic short 1 + * @param diagSh2 Diagnostic short 2 + * @param diagSh3 Diagnostic short 3 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic + i += put_float_by_index(diagFl1, i, msg->payload); //Diagnostic float 1 + i += put_float_by_index(diagFl2, i, msg->payload); //Diagnostic float 2 + i += put_float_by_index(diagFl3, i, msg->payload); //Diagnostic float 3 + i += put_int16_t_by_index(diagSh1, i, msg->payload); //Diagnostic short 1 + i += put_int16_t_by_index(diagSh2, i, msg->payload); //Diagnostic short 2 + i += put_int16_t_by_index(diagSh3, i, msg->payload); //Diagnostic short 3 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_diagnostic_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_diagnostic_t* diagnostic) +{ + return mavlink_msg_diagnostic_pack(system_id, component_id, msg, diagnostic->target, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan, uint8_t target, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3) +{ + mavlink_message_t msg; + mavlink_msg_diagnostic_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE DIAGNOSTIC UNPACKING + +/** + * @brief Get field target from diagnostic message + * + * @return The system reporting the diagnostic + */ +static inline uint8_t mavlink_msg_diagnostic_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field diagFl1 from diagnostic message + * + * @return Diagnostic float 1 + */ +static inline float mavlink_msg_diagnostic_get_diagFl1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field diagFl2 from diagnostic message + * + * @return Diagnostic float 2 + */ +static inline float mavlink_msg_diagnostic_get_diagFl2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field diagFl3 from diagnostic message + * + * @return Diagnostic float 3 + */ +static inline float mavlink_msg_diagnostic_get_diagFl3(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field diagSh1 from diagnostic message + * + * @return Diagnostic short 1 + */ +static inline int16_t mavlink_msg_diagnostic_get_diagSh1(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field diagSh2 from diagnostic message + * + * @return Diagnostic short 2 + */ +static inline int16_t mavlink_msg_diagnostic_get_diagSh2(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field diagSh3 from diagnostic message + * + * @return Diagnostic short 3 + */ +static inline int16_t mavlink_msg_diagnostic_get_diagSh3(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +static inline void mavlink_msg_diagnostic_decode(const mavlink_message_t* msg, mavlink_diagnostic_t* diagnostic) +{ + diagnostic->target = mavlink_msg_diagnostic_get_target(msg); + diagnostic->diagFl1 = mavlink_msg_diagnostic_get_diagFl1(msg); + diagnostic->diagFl2 = mavlink_msg_diagnostic_get_diagFl2(msg); + diagnostic->diagFl3 = mavlink_msg_diagnostic_get_diagFl3(msg); + diagnostic->diagSh1 = mavlink_msg_diagnostic_get_diagSh1(msg); + diagnostic->diagSh2 = mavlink_msg_diagnostic_get_diagSh2(msg); + diagnostic->diagSh3 = mavlink_msg_diagnostic_get_diagSh3(msg); +} diff --git a/libraries/mavlink/include/slugs/mavlink_msg_pilot_console.h b/libraries/mavlink/include/slugs/mavlink_msg_pilot_console.h new file mode 100644 index 0000000000..ecb4bddb0a --- /dev/null +++ b/libraries/mavlink/include/slugs/mavlink_msg_pilot_console.h @@ -0,0 +1,144 @@ +// MESSAGE PILOT_CONSOLE PACKING + +#define MAVLINK_MSG_ID_PILOT_CONSOLE 194 + +typedef struct __mavlink_pilot_console_t +{ + uint8_t target; ///< The system reporting the diagnostic + uint16_t dt; ///< Pilot's console throttle command + uint16_t dla; ///< Pilot's console left aileron command + uint16_t dra; ///< Pilot's console right aileron command + uint16_t dr; ///< Pilot's console rudder command + uint16_t de; ///< Pilot's console elevator command + +} mavlink_pilot_console_t; + + + +/** + * @brief Send a pilot_console message + * + * @param target The system reporting the diagnostic + * @param dt Pilot's console throttle command + * @param dla Pilot's console left aileron command + * @param dra Pilot's console right aileron command + * @param dr Pilot's console rudder command + * @param de Pilot's console elevator command + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_pilot_console_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PILOT_CONSOLE; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic + i += put_uint16_t_by_index(dt, i, msg->payload); //Pilot's console throttle command + i += put_uint16_t_by_index(dla, i, msg->payload); //Pilot's console left aileron command + i += put_uint16_t_by_index(dra, i, msg->payload); //Pilot's console right aileron command + i += put_uint16_t_by_index(dr, i, msg->payload); //Pilot's console rudder command + i += put_uint16_t_by_index(de, i, msg->payload); //Pilot's console elevator command + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_pilot_console_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pilot_console_t* pilot_console) +{ + return mavlink_msg_pilot_console_pack(system_id, component_id, msg, pilot_console->target, pilot_console->dt, pilot_console->dla, pilot_console->dra, pilot_console->dr, pilot_console->de); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_pilot_console_send(mavlink_channel_t chan, uint8_t target, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de) +{ + mavlink_message_t msg; + mavlink_msg_pilot_console_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, dt, dla, dra, dr, de); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PILOT_CONSOLE UNPACKING + +/** + * @brief Get field target from pilot_console message + * + * @return The system reporting the diagnostic + */ +static inline uint8_t mavlink_msg_pilot_console_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field dt from pilot_console message + * + * @return Pilot's console throttle command + */ +static inline uint16_t mavlink_msg_pilot_console_get_dt(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field dla from pilot_console message + * + * @return Pilot's console left aileron command + */ +static inline uint16_t mavlink_msg_pilot_console_get_dla(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field dra from pilot_console message + * + * @return Pilot's console right aileron command + */ +static inline uint16_t mavlink_msg_pilot_console_get_dra(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field dr from pilot_console message + * + * @return Pilot's console rudder command + */ +static inline uint16_t mavlink_msg_pilot_console_get_dr(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field de from pilot_console message + * + * @return Pilot's console elevator command + */ +static inline uint16_t mavlink_msg_pilot_console_get_de(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_pilot_console_decode(const mavlink_message_t* msg, mavlink_pilot_console_t* pilot_console) +{ + pilot_console->target = mavlink_msg_pilot_console_get_target(msg); + pilot_console->dt = mavlink_msg_pilot_console_get_dt(msg); + pilot_console->dla = mavlink_msg_pilot_console_get_dla(msg); + pilot_console->dra = mavlink_msg_pilot_console_get_dra(msg); + pilot_console->dr = mavlink_msg_pilot_console_get_dr(msg); + pilot_console->de = mavlink_msg_pilot_console_get_de(msg); +} diff --git a/libraries/mavlink/include/slugs/mavlink_msg_pwm_commands.h b/libraries/mavlink/include/slugs/mavlink_msg_pwm_commands.h new file mode 100644 index 0000000000..393b1b1955 --- /dev/null +++ b/libraries/mavlink/include/slugs/mavlink_msg_pwm_commands.h @@ -0,0 +1,229 @@ +// MESSAGE PWM_COMMANDS PACKING + +#define MAVLINK_MSG_ID_PWM_COMMANDS 195 + +typedef struct __mavlink_pwm_commands_t +{ + uint8_t target; ///< The system reporting the diagnostic + uint16_t dt_c; ///< AutoPilot's throttle command + uint16_t dla_c; ///< AutoPilot's left aileron command + uint16_t dra_c; ///< AutoPilot's right aileron command + uint16_t dr_c; ///< AutoPilot's rudder command + uint16_t dle_c; ///< AutoPilot's left elevator command + uint16_t dre_c; ///< AutoPilot's right elevator command + uint16_t dlf_c; ///< AutoPilot's left flap command + uint16_t drf_c; ///< AutoPilot's right flap command + uint16_t aux1; ///< AutoPilot's aux1 command + uint16_t aux2; ///< AutoPilot's aux2 command + +} mavlink_pwm_commands_t; + + + +/** + * @brief Send a pwm_commands message + * + * @param target The system reporting the diagnostic + * @param dt_c AutoPilot's throttle command + * @param dla_c AutoPilot's left aileron command + * @param dra_c AutoPilot's right aileron command + * @param dr_c AutoPilot's rudder command + * @param dle_c AutoPilot's left elevator command + * @param dre_c AutoPilot's right elevator command + * @param dlf_c AutoPilot's left flap command + * @param drf_c AutoPilot's right flap command + * @param aux1 AutoPilot's aux1 command + * @param aux2 AutoPilot's aux2 command + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_pwm_commands_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint16_t dt_c, uint16_t dla_c, uint16_t dra_c, uint16_t dr_c, uint16_t dle_c, uint16_t dre_c, uint16_t dlf_c, uint16_t drf_c, uint16_t aux1, uint16_t aux2) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PWM_COMMANDS; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic + i += put_uint16_t_by_index(dt_c, i, msg->payload); //AutoPilot's throttle command + i += put_uint16_t_by_index(dla_c, i, msg->payload); //AutoPilot's left aileron command + i += put_uint16_t_by_index(dra_c, i, msg->payload); //AutoPilot's right aileron command + i += put_uint16_t_by_index(dr_c, i, msg->payload); //AutoPilot's rudder command + i += put_uint16_t_by_index(dle_c, i, msg->payload); //AutoPilot's left elevator command + i += put_uint16_t_by_index(dre_c, i, msg->payload); //AutoPilot's right elevator command + i += put_uint16_t_by_index(dlf_c, i, msg->payload); //AutoPilot's left flap command + i += put_uint16_t_by_index(drf_c, i, msg->payload); //AutoPilot's right flap command + i += put_uint16_t_by_index(aux1, i, msg->payload); //AutoPilot's aux1 command + i += put_uint16_t_by_index(aux2, i, msg->payload); //AutoPilot's aux2 command + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_pwm_commands_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pwm_commands_t* pwm_commands) +{ + return mavlink_msg_pwm_commands_pack(system_id, component_id, msg, pwm_commands->target, pwm_commands->dt_c, pwm_commands->dla_c, pwm_commands->dra_c, pwm_commands->dr_c, pwm_commands->dle_c, pwm_commands->dre_c, pwm_commands->dlf_c, pwm_commands->drf_c, pwm_commands->aux1, pwm_commands->aux2); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_pwm_commands_send(mavlink_channel_t chan, uint8_t target, uint16_t dt_c, uint16_t dla_c, uint16_t dra_c, uint16_t dr_c, uint16_t dle_c, uint16_t dre_c, uint16_t dlf_c, uint16_t drf_c, uint16_t aux1, uint16_t aux2) +{ + mavlink_message_t msg; + mavlink_msg_pwm_commands_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, dt_c, dla_c, dra_c, dr_c, dle_c, dre_c, dlf_c, drf_c, aux1, aux2); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PWM_COMMANDS UNPACKING + +/** + * @brief Get field target from pwm_commands message + * + * @return The system reporting the diagnostic + */ +static inline uint8_t mavlink_msg_pwm_commands_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field dt_c from pwm_commands message + * + * @return AutoPilot's throttle command + */ +static inline uint16_t mavlink_msg_pwm_commands_get_dt_c(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field dla_c from pwm_commands message + * + * @return AutoPilot's left aileron command + */ +static inline uint16_t mavlink_msg_pwm_commands_get_dla_c(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field dra_c from pwm_commands message + * + * @return AutoPilot's right aileron command + */ +static inline uint16_t mavlink_msg_pwm_commands_get_dra_c(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field dr_c from pwm_commands message + * + * @return AutoPilot's rudder command + */ +static inline uint16_t mavlink_msg_pwm_commands_get_dr_c(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field dle_c from pwm_commands message + * + * @return AutoPilot's left elevator command + */ +static inline uint16_t mavlink_msg_pwm_commands_get_dle_c(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field dre_c from pwm_commands message + * + * @return AutoPilot's right elevator command + */ +static inline uint16_t mavlink_msg_pwm_commands_get_dre_c(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field dlf_c from pwm_commands message + * + * @return AutoPilot's left flap command + */ +static inline uint16_t mavlink_msg_pwm_commands_get_dlf_c(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field drf_c from pwm_commands message + * + * @return AutoPilot's right flap command + */ +static inline uint16_t mavlink_msg_pwm_commands_get_drf_c(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field aux1 from pwm_commands message + * + * @return AutoPilot's aux1 command + */ +static inline uint16_t mavlink_msg_pwm_commands_get_aux1(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field aux2 from pwm_commands message + * + * @return AutoPilot's aux2 command + */ +static inline uint16_t mavlink_msg_pwm_commands_get_aux2(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +static inline void mavlink_msg_pwm_commands_decode(const mavlink_message_t* msg, mavlink_pwm_commands_t* pwm_commands) +{ + pwm_commands->target = mavlink_msg_pwm_commands_get_target(msg); + pwm_commands->dt_c = mavlink_msg_pwm_commands_get_dt_c(msg); + pwm_commands->dla_c = mavlink_msg_pwm_commands_get_dla_c(msg); + pwm_commands->dra_c = mavlink_msg_pwm_commands_get_dra_c(msg); + pwm_commands->dr_c = mavlink_msg_pwm_commands_get_dr_c(msg); + pwm_commands->dle_c = mavlink_msg_pwm_commands_get_dle_c(msg); + pwm_commands->dre_c = mavlink_msg_pwm_commands_get_dre_c(msg); + pwm_commands->dlf_c = mavlink_msg_pwm_commands_get_dlf_c(msg); + pwm_commands->drf_c = mavlink_msg_pwm_commands_get_drf_c(msg); + pwm_commands->aux1 = mavlink_msg_pwm_commands_get_aux1(msg); + pwm_commands->aux2 = mavlink_msg_pwm_commands_get_aux2(msg); +} diff --git a/libraries/mavlink/include/slugs/mavlink_msg_sensor_bias.h b/libraries/mavlink/include/slugs/mavlink_msg_sensor_bias.h new file mode 100644 index 0000000000..a7560f14ff --- /dev/null +++ b/libraries/mavlink/include/slugs/mavlink_msg_sensor_bias.h @@ -0,0 +1,173 @@ +// MESSAGE SENSOR_BIAS PACKING + +#define MAVLINK_MSG_ID_SENSOR_BIAS 192 + +typedef struct __mavlink_sensor_bias_t +{ + uint8_t target; ///< The system reporting the biases + float axBias; ///< Accelerometer X bias (m/s) + float ayBias; ///< Accelerometer Y bias (m/s) + float azBias; ///< Accelerometer Z bias (m/s) + float gxBias; ///< Gyro X bias (rad/s) + float gyBias; ///< Gyro Y bias (rad/s) + float gzBias; ///< Gyro Z bias (rad/s) + +} mavlink_sensor_bias_t; + + + +/** + * @brief Send a sensor_bias message + * + * @param target The system reporting the biases + * @param axBias Accelerometer X bias (m/s) + * @param ayBias Accelerometer Y bias (m/s) + * @param azBias Accelerometer Z bias (m/s) + * @param gxBias Gyro X bias (rad/s) + * @param gyBias Gyro Y bias (rad/s) + * @param gzBias Gyro Z bias (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS; + + i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the biases + i += put_float_by_index(axBias, i, msg->payload); //Accelerometer X bias (m/s) + i += put_float_by_index(ayBias, i, msg->payload); //Accelerometer Y bias (m/s) + i += put_float_by_index(azBias, i, msg->payload); //Accelerometer Z bias (m/s) + i += put_float_by_index(gxBias, i, msg->payload); //Gyro X bias (rad/s) + i += put_float_by_index(gyBias, i, msg->payload); //Gyro Y bias (rad/s) + i += put_float_by_index(gzBias, i, msg->payload); //Gyro Z bias (rad/s) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_bias_t* sensor_bias) +{ + return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->target, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, uint8_t target, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias) +{ + mavlink_message_t msg; + mavlink_msg_sensor_bias_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, axBias, ayBias, azBias, gxBias, gyBias, gzBias); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SENSOR_BIAS UNPACKING + +/** + * @brief Get field target from sensor_bias message + * + * @return The system reporting the biases + */ +static inline uint8_t mavlink_msg_sensor_bias_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field axBias from sensor_bias message + * + * @return Accelerometer X bias (m/s) + */ +static inline float mavlink_msg_sensor_bias_get_axBias(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field ayBias from sensor_bias message + * + * @return Accelerometer Y bias (m/s) + */ +static inline float mavlink_msg_sensor_bias_get_ayBias(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field azBias from sensor_bias message + * + * @return Accelerometer Z bias (m/s) + */ +static inline float mavlink_msg_sensor_bias_get_azBias(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field gxBias from sensor_bias message + * + * @return Gyro X bias (rad/s) + */ +static inline float mavlink_msg_sensor_bias_get_gxBias(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field gyBias from sensor_bias message + * + * @return Gyro Y bias (rad/s) + */ +static inline float mavlink_msg_sensor_bias_get_gyBias(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field gzBias from sensor_bias message + * + * @return Gyro Z bias (rad/s) + */ +static inline float mavlink_msg_sensor_bias_get_gzBias(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_sensor_bias_decode(const mavlink_message_t* msg, mavlink_sensor_bias_t* sensor_bias) +{ + sensor_bias->target = mavlink_msg_sensor_bias_get_target(msg); + sensor_bias->axBias = mavlink_msg_sensor_bias_get_axBias(msg); + sensor_bias->ayBias = mavlink_msg_sensor_bias_get_ayBias(msg); + sensor_bias->azBias = mavlink_msg_sensor_bias_get_azBias(msg); + sensor_bias->gxBias = mavlink_msg_sensor_bias_get_gxBias(msg); + sensor_bias->gyBias = mavlink_msg_sensor_bias_get_gyBias(msg); + sensor_bias->gzBias = mavlink_msg_sensor_bias_get_gzBias(msg); +} diff --git a/libraries/mavlink/include/slugs/slugs.h b/libraries/mavlink/include/slugs/slugs.h new file mode 100644 index 0000000000..ac712f04dd --- /dev/null +++ b/libraries/mavlink/include/slugs/slugs.h @@ -0,0 +1,29 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Sunday, October 24 2010, 08:47 UTC + */ +#ifndef SLUGS_H +#define SLUGS_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_SLUGS + + +#include "../common/common.h" +#include "./mavlink_msg_cpu_load.h" +#include "./mavlink_msg_air_data.h" +#include "./mavlink_msg_sensor_bias.h" +#include "./mavlink_msg_diagnostic.h" +#include "./mavlink_msg_pilot_console.h" +#include "./mavlink_msg_pwm_commands.h" +#ifdef __cplusplus +} +#endif +#endif diff --git a/libraries/mavlink/include/ualberta/mavlink.h b/libraries/mavlink/include/ualberta/mavlink.h new file mode 100644 index 0000000000..1b074e88a1 --- /dev/null +++ b/libraries/mavlink/include/ualberta/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Monday, October 25 2010, 17:38 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "ualberta.h" + +#endif diff --git a/libraries/mavlink/include/ualberta/mavlink_msg_nav_filter_bias.h b/libraries/mavlink/include/ualberta/mavlink_msg_nav_filter_bias.h new file mode 100644 index 0000000000..0b614087f6 --- /dev/null +++ b/libraries/mavlink/include/ualberta/mavlink_msg_nav_filter_bias.h @@ -0,0 +1,182 @@ +// MESSAGE NAV_FILTER_BIAS PACKING + +#define MAVLINK_MSG_ID_NAV_FILTER_BIAS 220 + +typedef struct __mavlink_nav_filter_bias_t +{ + uint64_t usec; ///< Timestamp (microseconds) + float accel_0; ///< b_f[0] + float accel_1; ///< b_f[1] + float accel_2; ///< b_f[2] + float gyro_0; ///< b_f[0] + float gyro_1; ///< b_f[1] + float gyro_2; ///< b_f[2] + +} mavlink_nav_filter_bias_t; + + + +/** + * @brief Send a nav_filter_bias message + * + * @param usec Timestamp (microseconds) + * @param accel_0 b_f[0] + * @param accel_1 b_f[1] + * @param accel_2 b_f[2] + * @param gyro_0 b_f[0] + * @param gyro_1 b_f[1] + * @param gyro_2 b_f[2] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_filter_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS; + + i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds) + i += put_float_by_index(accel_0, i, msg->payload); //b_f[0] + i += put_float_by_index(accel_1, i, msg->payload); //b_f[1] + i += put_float_by_index(accel_2, i, msg->payload); //b_f[2] + i += put_float_by_index(gyro_0, i, msg->payload); //b_f[0] + i += put_float_by_index(gyro_1, i, msg->payload); //b_f[1] + i += put_float_by_index(gyro_2, i, msg->payload); //b_f[2] + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_nav_filter_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_filter_bias_t* nav_filter_bias) +{ + return mavlink_msg_nav_filter_bias_pack(system_id, component_id, msg, nav_filter_bias->usec, nav_filter_bias->accel_0, nav_filter_bias->accel_1, nav_filter_bias->accel_2, nav_filter_bias->gyro_0, nav_filter_bias->gyro_1, nav_filter_bias->gyro_2); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_nav_filter_bias_send(mavlink_channel_t chan, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2) +{ + mavlink_message_t msg; + mavlink_msg_nav_filter_bias_pack(mavlink_system.sysid, mavlink_system.compid, &msg, usec, accel_0, accel_1, accel_2, gyro_0, gyro_1, gyro_2); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE NAV_FILTER_BIAS UNPACKING + +/** + * @brief Get field usec from nav_filter_bias message + * + * @return Timestamp (microseconds) + */ +static inline uint64_t mavlink_msg_nav_filter_bias_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field accel_0 from nav_filter_bias message + * + * @return b_f[0] + */ +static inline float mavlink_msg_nav_filter_bias_get_accel_0(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field accel_1 from nav_filter_bias message + * + * @return b_f[1] + */ +static inline float mavlink_msg_nav_filter_bias_get_accel_1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field accel_2 from nav_filter_bias message + * + * @return b_f[2] + */ +static inline float mavlink_msg_nav_filter_bias_get_accel_2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field gyro_0 from nav_filter_bias message + * + * @return b_f[0] + */ +static inline float mavlink_msg_nav_filter_bias_get_gyro_0(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field gyro_1 from nav_filter_bias message + * + * @return b_f[1] + */ +static inline float mavlink_msg_nav_filter_bias_get_gyro_1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field gyro_2 from nav_filter_bias message + * + * @return b_f[2] + */ +static inline float mavlink_msg_nav_filter_bias_get_gyro_2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +static inline void mavlink_msg_nav_filter_bias_decode(const mavlink_message_t* msg, mavlink_nav_filter_bias_t* nav_filter_bias) +{ + nav_filter_bias->usec = mavlink_msg_nav_filter_bias_get_usec(msg); + nav_filter_bias->accel_0 = mavlink_msg_nav_filter_bias_get_accel_0(msg); + nav_filter_bias->accel_1 = mavlink_msg_nav_filter_bias_get_accel_1(msg); + nav_filter_bias->accel_2 = mavlink_msg_nav_filter_bias_get_accel_2(msg); + nav_filter_bias->gyro_0 = mavlink_msg_nav_filter_bias_get_gyro_0(msg); + nav_filter_bias->gyro_1 = mavlink_msg_nav_filter_bias_get_gyro_1(msg); + nav_filter_bias->gyro_2 = mavlink_msg_nav_filter_bias_get_gyro_2(msg); +} diff --git a/libraries/mavlink/include/ualberta/mavlink_msg_radio_calibration.h b/libraries/mavlink/include/ualberta/mavlink_msg_radio_calibration.h new file mode 100644 index 0000000000..f0cddbab5c --- /dev/null +++ b/libraries/mavlink/include/ualberta/mavlink_msg_radio_calibration.h @@ -0,0 +1,147 @@ +// MESSAGE RADIO_CALIBRATION PACKING + +#define MAVLINK_MSG_ID_RADIO_CALIBRATION 82 + +typedef struct __mavlink_radio_calibration_t +{ + float aileron[3]; ///< Aileron setpoints: high, center, low + float elevator[3]; ///< Elevator setpoints: high, center, low + float rudder[3]; ///< Rudder setpoints: high, center, low + float gyro[2]; ///< Tail gyro mode/gain setpoints: heading hold, rate mode + float pitch[5]; ///< Pitch curve setpoints (every 25%) + float throttle[5]; ///< Throttle curve setpoints (every 25%) + +} mavlink_radio_calibration_t; + +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN 3 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN 3 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN 3 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN 2 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN 5 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN 5 + + +/** + * @brief Send a radio_calibration message + * + * @param aileron Aileron setpoints: high, center, low + * @param elevator Elevator setpoints: high, center, low + * @param rudder Rudder setpoints: high, center, low + * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode + * @param pitch Pitch curve setpoints (every 25%) + * @param throttle Throttle curve setpoints (every 25%) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* aileron, const float* elevator, const float* rudder, const float* gyro, const float* pitch, const float* throttle) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION; + + i += put_array_by_index((int8_t*)aileron, sizeof(float)*3, i, msg->payload); //Aileron setpoints: high, center, low + i += put_array_by_index((int8_t*)elevator, sizeof(float)*3, i, msg->payload); //Elevator setpoints: high, center, low + i += put_array_by_index((int8_t*)rudder, sizeof(float)*3, i, msg->payload); //Rudder setpoints: high, center, low + i += put_array_by_index((int8_t*)gyro, sizeof(float)*2, i, msg->payload); //Tail gyro mode/gain setpoints: heading hold, rate mode + i += put_array_by_index((int8_t*)pitch, sizeof(float)*5, i, msg->payload); //Pitch curve setpoints (every 25%) + i += put_array_by_index((int8_t*)throttle, sizeof(float)*5, i, msg->payload); //Throttle curve setpoints (every 25%) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_radio_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_calibration_t* radio_calibration) +{ + return mavlink_msg_radio_calibration_pack(system_id, component_id, msg, radio_calibration->aileron, radio_calibration->elevator, radio_calibration->rudder, radio_calibration->gyro, radio_calibration->pitch, radio_calibration->throttle); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_radio_calibration_send(mavlink_channel_t chan, const float* aileron, const float* elevator, const float* rudder, const float* gyro, const float* pitch, const float* throttle) +{ + mavlink_message_t msg; + mavlink_msg_radio_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, aileron, elevator, rudder, gyro, pitch, throttle); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RADIO_CALIBRATION UNPACKING + +/** + * @brief Get field aileron from radio_calibration message + * + * @return Aileron setpoints: high, center, low + */ +static inline uint16_t mavlink_msg_radio_calibration_get_aileron(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload, sizeof(float)*3); + return sizeof(float)*3; +} + +/** + * @brief Get field elevator from radio_calibration message + * + * @return Elevator setpoints: high, center, low + */ +static inline uint16_t mavlink_msg_radio_calibration_get_elevator(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)*3, sizeof(float)*3); + return sizeof(float)*3; +} + +/** + * @brief Get field rudder from radio_calibration message + * + * @return Rudder setpoints: high, center, low + */ +static inline uint16_t mavlink_msg_radio_calibration_get_rudder(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3, sizeof(float)*3); + return sizeof(float)*3; +} + +/** + * @brief Get field gyro from radio_calibration message + * + * @return Tail gyro mode/gain setpoints: heading hold, rate mode + */ +static inline uint16_t mavlink_msg_radio_calibration_get_gyro(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3+sizeof(float)*3, sizeof(float)*2); + return sizeof(float)*2; +} + +/** + * @brief Get field pitch from radio_calibration message + * + * @return Pitch curve setpoints (every 25%) + */ +static inline uint16_t mavlink_msg_radio_calibration_get_pitch(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3+sizeof(float)*3+sizeof(float)*2, sizeof(float)*5); + return sizeof(float)*5; +} + +/** + * @brief Get field throttle from radio_calibration message + * + * @return Throttle curve setpoints (every 25%) + */ +static inline uint16_t mavlink_msg_radio_calibration_get_throttle(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3+sizeof(float)*3+sizeof(float)*2+sizeof(float)*5, sizeof(float)*5); + return sizeof(float)*5; +} + +static inline void mavlink_msg_radio_calibration_decode(const mavlink_message_t* msg, mavlink_radio_calibration_t* radio_calibration) +{ + mavlink_msg_radio_calibration_get_aileron(msg, radio_calibration->aileron); + mavlink_msg_radio_calibration_get_elevator(msg, radio_calibration->elevator); + mavlink_msg_radio_calibration_get_rudder(msg, radio_calibration->rudder); + mavlink_msg_radio_calibration_get_gyro(msg, radio_calibration->gyro); + mavlink_msg_radio_calibration_get_pitch(msg, radio_calibration->pitch); + mavlink_msg_radio_calibration_get_throttle(msg, radio_calibration->throttle); +} diff --git a/libraries/mavlink/include/ualberta/mavlink_msg_request_radio_calibration.h b/libraries/mavlink/include/ualberta/mavlink_msg_request_radio_calibration.h new file mode 100644 index 0000000000..6fa5dd08b3 --- /dev/null +++ b/libraries/mavlink/include/ualberta/mavlink_msg_request_radio_calibration.h @@ -0,0 +1,59 @@ +// MESSAGE REQUEST_RADIO_CALIBRATION PACKING + +#define MAVLINK_MSG_ID_REQUEST_RADIO_CALIBRATION 83 + +typedef struct __mavlink_request_radio_calibration_t +{ + uint8_t unused; ///< Unused field. Included to prevent compile time warnings + +} mavlink_request_radio_calibration_t; + + + +/** + * @brief Send a request_radio_calibration message + * + * @param unused Unused field. Included to prevent compile time warnings + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_radio_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t unused) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_REQUEST_RADIO_CALIBRATION; + + i += put_uint8_t_by_index(unused, i, msg->payload); //Unused field. Included to prevent compile time warnings + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_request_radio_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_radio_calibration_t* request_radio_calibration) +{ + return mavlink_msg_request_radio_calibration_pack(system_id, component_id, msg, request_radio_calibration->unused); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_radio_calibration_send(mavlink_channel_t chan, uint8_t unused) +{ + mavlink_message_t msg; + mavlink_msg_request_radio_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, unused); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE REQUEST_RADIO_CALIBRATION UNPACKING + +/** + * @brief Get field unused from request_radio_calibration message + * + * @return Unused field. Included to prevent compile time warnings + */ +static inline uint8_t mavlink_msg_request_radio_calibration_get_unused(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +static inline void mavlink_msg_request_radio_calibration_decode(const mavlink_message_t* msg, mavlink_request_radio_calibration_t* request_radio_calibration) +{ + request_radio_calibration->unused = mavlink_msg_request_radio_calibration_get_unused(msg); +} diff --git a/libraries/mavlink/include/ualberta/mavlink_msg_request_rc_channels.h b/libraries/mavlink/include/ualberta/mavlink_msg_request_rc_channels.h new file mode 100644 index 0000000000..20267a08c4 --- /dev/null +++ b/libraries/mavlink/include/ualberta/mavlink_msg_request_rc_channels.h @@ -0,0 +1,59 @@ +// MESSAGE REQUEST_RC_CHANNELS PACKING + +#define MAVLINK_MSG_ID_REQUEST_RC_CHANNELS 221 + +typedef struct __mavlink_request_rc_channels_t +{ + uint8_t enabled; ///< True: start sending data; False: stop sending data + +} mavlink_request_rc_channels_t; + + + +/** + * @brief Send a request_rc_channels message + * + * @param enabled True: start sending data; False: stop sending data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t enabled) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_REQUEST_RC_CHANNELS; + + i += put_uint8_t_by_index(enabled, i, msg->payload); //True: start sending data; False: stop sending data + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +static inline uint16_t mavlink_msg_request_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_rc_channels_t* request_rc_channels) +{ + return mavlink_msg_request_rc_channels_pack(system_id, component_id, msg, request_rc_channels->enabled); +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_rc_channels_send(mavlink_channel_t chan, uint8_t enabled) +{ + mavlink_message_t msg; + mavlink_msg_request_rc_channels_pack(mavlink_system.sysid, mavlink_system.compid, &msg, enabled); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE REQUEST_RC_CHANNELS UNPACKING + +/** + * @brief Get field enabled from request_rc_channels message + * + * @return True: start sending data; False: stop sending data + */ +static inline uint8_t mavlink_msg_request_rc_channels_get_enabled(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +static inline void mavlink_msg_request_rc_channels_decode(const mavlink_message_t* msg, mavlink_request_rc_channels_t* request_rc_channels) +{ + request_rc_channels->enabled = mavlink_msg_request_rc_channels_get_enabled(msg); +} diff --git a/libraries/mavlink/include/ualberta/ualberta.h b/libraries/mavlink/include/ualberta/ualberta.h new file mode 100644 index 0000000000..981bc0a925 --- /dev/null +++ b/libraries/mavlink/include/ualberta/ualberta.h @@ -0,0 +1,27 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Monday, October 25 2010, 17:38 UTC + */ +#ifndef UALBERTA_H +#define UALBERTA_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_UALBERTA + + +#include "../common/common.h" +#include "./mavlink_msg_nav_filter_bias.h" +#include "./mavlink_msg_request_rc_channels.h" +#include "./mavlink_msg_radio_calibration.h" +#include "./mavlink_msg_request_radio_calibration.h" +#ifdef __cplusplus +} +#endif +#endif diff --git a/libraries/mavlink/message_definitions/ardupilotmega.xml b/libraries/mavlink/message_definitions/ardupilotmega.xml new file mode 100644 index 0000000000..39d96eab51 --- /dev/null +++ b/libraries/mavlink/message_definitions/ardupilotmega.xml @@ -0,0 +1,6 @@ + + + common.xml + + + diff --git a/libraries/mavlink/message_definitions/common.xml b/libraries/mavlink/message_definitions/common.xml new file mode 100644 index 0000000000..95c3cbd3b4 --- /dev/null +++ b/libraries/mavlink/message_definitions/common.xml @@ -0,0 +1,411 @@ + + + + + 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 + + + + 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 + + + + 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 + + + + 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 + + + + 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 + + + + 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 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) + X acceleration (mg raw) + Y acceleration (mg raw) + Z acceleration (mg raw) + Angular speed around X axis (adc units) + Angular speed around Y axis (adc units) + Angular speed around Z axis (adc units) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + + 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) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Differential pressure 2 (hectopascal) + + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (microseconds) + 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). + Timestamp (microseconds since unix epoch) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + + 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. + Timestamp (microseconds since unix epoch) + 0-1: no fix, 2: 2D fix, 3: 3D fix + X Position + Y Position + Z Position in meters + Uncertainty in meters of latitude + Uncertainty in meters of longitude + Overall speed + Heading, in FIXME + + + + 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. 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 filtered global position (e.g. fused GPS and accelerometers). + Timestamp (microseconds since unix epoch) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + + 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) + Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off) + 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% + + + + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint. It cannot be used to set a waypoint, use WAYPOINT_SET for this purpose. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon. The global and body frame are related as: positive Z-down, positive X(front looking north, positive Y(body:right) looking east. Therefore y encodes in global mode the latitude, whereas x encodes the longitude and z the GPS altitude (WGS84). + 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_ACTION in mavlink_types.h + Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint + Direction of the orbit circling: 0: clockwise, 1: counter-clockwise + For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters + For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds + false:0, true:1 + local: x position, global: longitude + y position: global: latitude + z position: global: altitude + yaw orientation in radians, 0 = NORTH + autocontinue to next wp + + + + 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 x position + global y position + global z position + global yaw orientation in radians, 0 = NORTH + local x position that matches the global x position + local y position that matches the global y position + local z position that matches the global z position + local yaw that matches the global yaw orientation + + + + + + 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 1 + y position 1 + z position 1 + x position 2 + + + + Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS. + x position 1 + y position 1 + z position 1 + x position 2 + + + + The output of the attitude controller. This output is the control response the controller currently generates and the attitude the MAV would take if it is under control of the attitude controller. The primary use of this message is to check the response and signs of the controller before the actual flight. + 1: enabled, 0: disabled + Attitude roll: -128: -100%, 127: +100% + Attitude pitch: -128: -100%, 127: +100% + Attitude yaw: -128: -100%, 127: +100% + Attitude thrust: -128: -100%, 127: +100% + + + + The output of the position controller. The primary use of this message is to check the response and signs of the controller before the actual flight. + 1: enabled, 0: disabled + Position x: -128: -100%, 127: +100% + Position y: -128: -100%, 127: +100% + Position z: -128: -100%, 127: +100% + Position yaw: -128: -100%, 127: +100% + + + + 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 + The requested interval between two messages of this type + 1 to start sending, 0 to stop sending. + + + + The system which should auto-calibrate +The system component which should auto-calibrate + The current ground-truth rpm + The axis to calibrate: 0 roll, 1 pitch, 2 yaw + The time to average over in ms + + + + The system which should auto-calibrate +The system component which should auto-calibrate + The time to average over in ms + + + + 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 + + + + + + + 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/libraries/mavlink/message_definitions/mavlink_standard_proposal.xml b/libraries/mavlink/message_definitions/mavlink_standard_proposal.xml new file mode 100644 index 0000000000..43f0a0435d --- /dev/null +++ b/libraries/mavlink/message_definitions/mavlink_standard_proposal.xml @@ -0,0 +1,275 @@ + + + + + The heartbeat message just shows that a system is present. + 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 + + + + A ping message either requesting or responding to a ping. + 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 + The onboard software version + + + + + 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 + Failure code description, see MAV_FAILURE ENUM + Motor block status flag + Dropped packets + + + + Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h + 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 system setting the mode + The new navigation mode + + + + Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. + System ID + Component ID + Onboard parameter id + Onboard parameter value + + + + Set the current parameter value (currently active in RAM) PERMANTLY to EEPROM/HDD. It will be the new default value. + System ID + Component ID + Onboard parameter id + + + + Set PID values. + System ID + Component ID + PID ID + P + I + D + + + + Trim values to scale the RAW RC channel values. 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 id + RC channel 1 min value, in microseconds + RC channel 1 zero value, in microseconds + RC channel 1 max value, in microseconds + + + + Mapping defining which functions each RC channel has. + System ID + Component ID + RC channel id + RC channel function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h + + + + Message setting a waypoint. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon. The global and body frame are related as: positive Z-down, positive X(front looking north, positive Y(body:right) looking east. Therefore x encodes in global mode the latitude, whereas y encodes the longitude and z the altitude over ground. + System ID + Component ID + Waypoint ID + 0: global (GPS), 1: local, 2: global orbit, 3: local orbit + Orbit to circle around the waypoint, in meters + Time that the MAV should stay inside the orbit before advancing, in milliseconds + 0: No orbit, 1: Right Orbit, 2: Left Orbit + false:0, true:1 + local: x position, global: longitude + y position: global: latitude + z position: global: altitude + autocontinue to next wp + + + + System ID + Component ID + Waypoint ID + + + + System ID + Component ID + + + + The system executing the action + Component ID + The action id + + + + The system executing the action + Component ID + The id of the action being successfully executed and acknowledged + + + + Request to read the onboard parameters. + System ID + Component ID + Onboard parameter id + + + + Emit the value of a onboard parameter. + Onboard parameter id + Onboard parameter value + + + + Request all parameters of this component. + System ID + Component ID + 0: All parameters, else report a subset of parameters as defined in MAVLIN_SUBSET_PARAM enum + + + + Report PID controller values. + PID ID + P + I + D + + + + Report trim values to scale the RAW RC channel values. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + RC channel id + RC channel 1 min value, in microseconds + RC channel 1 zero value, in microseconds + RC channel 1 max value, in microseconds + + + + Report the mapping defining which functions each RC channel has. + RC channel id + RC channel function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h + + + + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint. It cannot be used to set a waypoint, use WAYPOINT_SET for this purpose. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon. The global and body frame are related as: positive Z-down, positive X(front looking north, positive Y(body:right) looking east. Therefore x encodes in global mode the latitude, whereas y encodes the longitude and z the altitude over ground. + Waypoint ID + 0: global (GPS), 1: local, 2: global orbit, 3: local orbit + Orbit to circle around the waypoint, in meters + Time that the MAV should stay inside the orbit before advancing, in milliseconds + 0: No orbit, 1: Right Orbit, 2: Left Orbit + false:0, true:1 + local: x position, global: longitude + y position: global: latitude + z position: global: altitude + autocontinue to next wp + + + + Message emmited by a system to anounce eit + Waypoint ID + Waypoint status: 0: Ok, 1: Reached, 2: Orbit time expired, 254: Error + + + + X acceleration (mg raw) + Y acceleration (mg raw) + Z acceleration (mg raw) + Angular speed around X axis (adc units) + Angular speed around Y axis (adc units) + Angular speed around Z axis (adc units) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + + Timestamp (microseconds since UNIX epoch) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Differential pressure 2 (hectopascal) + + + + 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. + 0-1: no fix, 2: 2D fix, 3: 3D fix + X Position + Y Position + Z Position in meters + Uncertainty in meters of latitude + Uncertainty in meters of longitude + Overall speed + Heading, in FIXME + + + + 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. + 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 attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (microseconds) + 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). + Position type: 0: Local, 1: Global + X (long) Position + Y (lat) Position + Z (alt) Position + Vx + Vy + Vz + + + + 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 3 value, in microseconds + RC channel 3 value, in microseconds + + + + + + + Severity of status, 0 = info message, 255 = critical fault + Status text message, without null termination character + + + + + index of debug variable + DEBUG value + + + + \ No newline at end of file diff --git a/libraries/mavlink/message_definitions/pixhawk.xml b/libraries/mavlink/message_definitions/pixhawk.xml new file mode 100644 index 0000000000..97a74ae219 --- /dev/null +++ b/libraries/mavlink/message_definitions/pixhawk.xml @@ -0,0 +1,228 @@ + + +common.xml + + + 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 + The requested interval between two messages of this type + 1 to start sending, 0 to stop sending. + + + + The system which should auto-calibrate +The system component which should auto-calibrate + The current ground-truth rpm + The axis to calibrate: 0 roll, 1 pitch, 2 yaw + The time to average over in ms + + + + The system which should auto-calibrate +The system component which should auto-calibrate + The time to average over in ms + + + + 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 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 + + + + Name + Timestamp + x + y + z + + + + Camera id + Camera mode: 0 = auto, 1 = manual + Trigger pin, 0-3 for PtGrey FireFly + Shutter interval, in microseconds + Exposure time, in microseconds + Camera gain + + + + Timestamp + IMU seq + Roll angle in rad + Pitch angle in rad + + + + 0 to disable, 1 to enable + + + + Camera id + Camera # (starts with 0) + Timestamp + Until which timestamp this buffer will stay valid + The image sequence number + Position of the image in the buffer, starts with 0 + Image width + Image height + Image depth + Image channels + Shared memory area key + Exposure time, in microseconds + Camera gain + Roll angle in rad + Pitch angle in rad + + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + + Message sent to the MAV to set a new position as reference for the controller + System ID + Component ID + ID of waypoint, 0 for plain position + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + + Message sent to the MAV to set a new offset from the currently controlled position + System ID + Component ID + x position offset + y position offset + z position offset + yaw orientation offset in radians, 0 = NORTH + + + + + ID of waypoint, 0 for plain position + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + + ID + x position + y position + z position + roll orientation + pitch orientation + yaw orientation + + + + ADC1 (J405 ADC3, LPC2148 AD0.6) + ADC2 (J405 ADC5, LPC2148 AD0.2) + ADC3 (J405 ADC6, LPC2148 AD0.1) + ADC4 (J405 ADC7, LPC2148 AD1.3) + Battery voltage + Temperature (degrees celcius) + Barometric pressure (hecto Pascal) + + + + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Number of I2C errors since startup +Number of I2C errors since startup + Number of I2C errors since startup +Number of I2C errors since startup + Number of I2C errors since startup + + + + 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 + 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 + + + + Watchdog ID + Number of processes + + + + Watchdog ID + Process ID + Process name + Process arguments + Timeout (seconds) + + + + Watchdog ID + Process ID + Is running / finished / suspended / crashed + Is muted + PID + Number of crashes + + + + Target system ID + Watchdog ID + Process ID + Command ID + + + + 0: Pattern, 1: Letter + Confidence of detection + Pattern file name + Accepted as true detection, 0 no, 1 yes + + + + diff --git a/libraries/mavlink/message_definitions/slugs.xml b/libraries/mavlink/message_definitions/slugs.xml new file mode 100644 index 0000000000..1812b7c303 --- /dev/null +++ b/libraries/mavlink/message_definitions/slugs.xml @@ -0,0 +1,67 @@ + + +common.xml + + + Sensor and DSC control loads. + The system reporting the CPU load + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + Air data for altitude and airspeed computation. + The system reporting the air data + Dynamic pressure (Pa) + Static pressure (Pa) + Board temperature + + + + Accelerometer and gyro biases. + The system reporting the 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. + The system reporting the diagnostic + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Pilot console PWM messges. + The system reporting the diagnostic + Pilot's console throttle command + Pilot's console left aileron command + Pilot's console right aileron command + Pilot's console rudder command + Pilot's console elevator command + + + + PWM Commands from the AP to the control surfaces. + The system reporting the diagnostic + AutoPilot's throttle command + AutoPilot's left aileron command + AutoPilot's right aileron command + AutoPilot's rudder command + AutoPilot's left elevator command + AutoPilot's right elevator command + AutoPilot's left flap command + AutoPilot's right flap command + AutoPilot's aux1 command + AutoPilot's aux2 command + + + \ No newline at end of file diff --git a/libraries/mavlink/message_definitions/ualberta.xml b/libraries/mavlink/message_definitions/ualberta.xml new file mode 100644 index 0000000000..ef28d6e914 --- /dev/null +++ b/libraries/mavlink/message_definitions/ualberta.xml @@ -0,0 +1,29 @@ + + + common.xml + + + 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] + + + Request raw and normalized rc data from the UAV + True: start sending data; False: stop sending data + + + Complete set of calibration parameters for the radio + Aileron setpoints: high, center, low + Elevator setpoints: high, center, low + Rudder setpoints: high, center, low + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + +