diff --git a/.gitignore b/.gitignore
index 71326517f2..afd63e06a0 100644
--- a/.gitignore
+++ b/.gitignore
@@ -34,5 +34,8 @@ mavlink/include/mavlink/v0.9/
/Documentation/html/
/Documentation/doxygen*objdb*tmp
.tags
+tags
.tags_sorted_by_file
.pydevproject
+.ropeproject
+*.orig
diff --git a/.ycm_extra_conf.py b/.ycm_extra_conf.py
new file mode 100644
index 0000000000..fed5cd28a0
--- /dev/null
+++ b/.ycm_extra_conf.py
@@ -0,0 +1,173 @@
+# This file is NOT licensed under the GPLv3, which is the license for the rest
+# of YouCompleteMe.
+#
+# Here's the license text for this file:
+#
+# This is free and unencumbered software released into the public domain.
+#
+# Anyone is free to copy, modify, publish, use, compile, sell, or
+# distribute this software, either in source code form or as a compiled
+# binary, for any purpose, commercial or non-commercial, and by any
+# means.
+#
+# In jurisdictions that recognize copyright laws, the author or authors
+# of this software dedicate any and all copyright interest in the
+# software to the public domain. We make this dedication for the benefit
+# of the public at large and to the detriment of our heirs and
+# successors. We intend this dedication to be an overt act of
+# relinquishment in perpetuity of all present and future rights to this
+# software under copyright law.
+#
+# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+# EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+# MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
+# IN NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR
+# OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
+# ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
+# OTHER DEALINGS IN THE SOFTWARE.
+#
+# For more information, please refer to
+
+import os
+import ycm_core
+
+# These are the compilation flags that will be used in case there's no
+# compilation database set (by default, one is not set).
+# CHANGE THIS LIST OF FLAGS. YES, THIS IS THE DROID YOU HAVE BEEN LOOKING FOR.
+flags = [
+'-Wall',
+'-Wextra',
+'-Werror',
+#'-Wc++98-compat',
+'-Wno-long-long',
+'-Wno-variadic-macros',
+'-fexceptions',
+'-DNDEBUG',
+# You 100% do NOT need -DUSE_CLANG_COMPLETER in your flags; only the YCM
+# source code needs it.
+#'-DUSE_CLANG_COMPLETER',
+# THIS IS IMPORTANT! Without a "-std=" flag, clang won't know which
+# language to use when compiling headers. So it will guess. Badly. So C++
+# headers will be compiled as C headers. You don't want that so ALWAYS specify
+# a "-std=".
+# For a C project, you would set this to something like 'c99' instead of
+# 'c++11'.
+'-std=c++11',
+# ...and the same thing goes for the magic -x option which specifies the
+# language that the files to be compiled are written in. This is mostly
+# relevant for c++ headers.
+# For a C project, you would set this to 'c' instead of 'c++'.
+'-x',
+'c++',
+'-undef', # get rid of standard definitions to allow us to include arm math header
+'-I', os.path.join(os.path.expanduser("~"),'gcc-arm-none-eabi-4_7-2013q3/arm-none-eabi/include'),
+'-I', 'Build/px4io-v1_default.build/nuttx-export/include/',
+'-I', 'Build/px4io-v2_default.build/nuttx-export/include/',
+'-I', './NuttX/nuttx/arch/arm/include',
+'-include', './src/include/visibility.h',
+'-I', './src',
+'-I', './src/modules',
+'-I', './src/include',
+'-I', './src/lib',
+'-I', './NuttX',
+]
+
+
+# Set this to the absolute path to the folder (NOT the file!) containing the
+# compile_commands.json file to use that instead of 'flags'. See here for
+# more details: http://clang.llvm.org/docs/JSONCompilationDatabase.html
+#
+# Most projects will NOT need to set this to anything; you can just change the
+# 'flags' list of compilation flags. Notice that YCM itself uses that approach.
+compilation_database_folder = ''
+
+if os.path.exists( compilation_database_folder ):
+ database = ycm_core.CompilationDatabase( compilation_database_folder )
+else:
+ database = None
+
+SOURCE_EXTENSIONS = [ '.cpp', '.cxx', '.cc', '.c', '.m', '.mm' ]
+
+def DirectoryOfThisScript():
+ return os.path.dirname( os.path.abspath( __file__ ) )
+
+
+def MakeRelativePathsInFlagsAbsolute( flags, working_directory ):
+ if not working_directory:
+ return list( flags )
+ new_flags = []
+ make_next_absolute = False
+ path_flags = [ '-isystem', '-I', '-iquote', '--sysroot=' ]
+ for flag in flags:
+ new_flag = flag
+
+ if make_next_absolute:
+ make_next_absolute = False
+ if not flag.startswith( '/' ):
+ new_flag = os.path.join( working_directory, flag )
+
+ for path_flag in path_flags:
+ if flag == path_flag:
+ make_next_absolute = True
+ break
+
+ if flag.startswith( path_flag ):
+ path = flag[ len( path_flag ): ]
+ new_flag = path_flag + os.path.join( working_directory, path )
+ break
+
+ if new_flag:
+ new_flags.append( new_flag )
+ return new_flags
+
+
+def IsHeaderFile( filename ):
+ extension = os.path.splitext( filename )[ 1 ]
+ return extension in [ '.h', '.hxx', '.hpp', '.hh' ]
+
+
+def GetCompilationInfoForFile( filename ):
+ # The compilation_commands.json file generated by CMake does not have entries
+ # for header files. So we do our best by asking the db for flags for a
+ # corresponding source file, if any. If one exists, the flags for that file
+ # should be good enough.
+ if IsHeaderFile( filename ):
+ basename = os.path.splitext( filename )[ 0 ]
+ for extension in SOURCE_EXTENSIONS:
+ replacement_file = basename + extension
+ if os.path.exists( replacement_file ):
+ compilation_info = database.GetCompilationInfoForFile(
+ replacement_file )
+ if compilation_info.compiler_flags_:
+ return compilation_info
+ return None
+ return database.GetCompilationInfoForFile( filename )
+
+
+def FlagsForFile( filename, **kwargs ):
+ if database:
+ # Bear in mind that compilation_info.compiler_flags_ does NOT return a
+ # python list, but a "list-like" StringVec object
+ compilation_info = GetCompilationInfoForFile( filename )
+ if not compilation_info:
+ return None
+
+ final_flags = MakeRelativePathsInFlagsAbsolute(
+ compilation_info.compiler_flags_,
+ compilation_info.compiler_working_dir_ )
+
+ # NOTE: This is just for YouCompleteMe; it's highly likely that your project
+ # does NOT need to remove the stdlib flag. DO NOT USE THIS IN YOUR
+ # ycm_extra_conf IF YOU'RE NOT 100% SURE YOU NEED IT.
+ #try:
+ # final_flags.remove( '-stdlib=libc++' )
+ #except ValueError:
+ # pass
+ else:
+ relative_to = DirectoryOfThisScript()
+ final_flags = MakeRelativePathsInFlagsAbsolute( flags, relative_to )
+
+ return {
+ 'flags': final_flags,
+ 'do_cache': True
+ }
diff --git a/Debug/NuttX b/Debug/NuttX
index 3b95e96b2f..d34e9f5b4b 100644
--- a/Debug/NuttX
+++ b/Debug/NuttX
@@ -34,10 +34,10 @@ define _showheap
else
set $MM_ALLOC_BIT = 0x80000000
end
- printf "HEAP %d %p - %p\n", $index, g_heapstart[$index], g_heapend[$index]
+ printf "HEAP %d %p - %p\n", $index, g_mmheap.mm_heapstart[$index], g_mmheap.mm_heapend[$index]
printf "ptr size\n"
- set $node = (char *)g_heapstart[$index] + sizeof(struct mm_allocnode_s)
- while $node < g_heapend[$index]
+ set $node = (char *)g_mmheap.mm_heapstart[$index] + sizeof(struct mm_allocnode_s)
+ while $node < g_mmheap.mm_heapend[$index]
printf " %p", $node
set $nodestruct = (struct mm_allocnode_s *)$node
printf " %u", $nodestruct->size
@@ -47,7 +47,7 @@ define _showheap
else
set $used = $used + $nodestruct->size
end
- if ($nodestruct->size > g_heapsize) || (($node + $nodestruct->size) > g_heapend[$index])
+ if ($nodestruct->size > g_mmheap.mm_heapsize) || (($node + $nodestruct->size) > g_mmheap.mm_heapend[$index])
printf " (BAD SIZE)"
end
printf "\n"
@@ -59,7 +59,7 @@ define _showheap
end
define showheap
- set $nheaps = sizeof(g_heapstart) / sizeof(g_heapstart[0])
+ set $nheaps = sizeof(g_mmheap.mm_heapstart) / sizeof(g_mmheap.mm_heapstart[0])
printf "Printing %d heaps\n", $nheaps
set $heapindex = (int)0
while $heapindex < $nheaps
diff --git a/Debug/Nuttx.py b/Debug/Nuttx.py
index 093edd0e09..7cc21b99f4 100644
--- a/Debug/Nuttx.py
+++ b/Debug/Nuttx.py
@@ -306,12 +306,15 @@ class NX_show_heap (gdb.Command):
def __init__(self):
super(NX_show_heap, self).__init__('show heap', gdb.COMMAND_USER)
- if gdb.lookup_type('struct mm_allocnode_s').sizeof == 8:
- self._allocflag = 0x80000000
- self._allocnodesize = 8
- else:
+ struct_mm_allocnode_s = gdb.lookup_type('struct mm_allocnode_s')
+ preceding_size = struct_mm_allocnode_s['preceding'].type.sizeof
+ if preceding_size == 2:
self._allocflag = 0x8000
- self._allocnodesize = 4
+ elif preceding_size == 4:
+ self._allocflag = 0x80000000
+ else:
+ raise gdb.GdbError('invalid mm_allocnode_s.preceding size %u' % preceding_size)
+ self._allocnodesize = struct_mm_allocnode_s.sizeof
def _node_allocated(self, allocnode):
if allocnode['preceding'] & self._allocflag:
@@ -333,7 +336,8 @@ class NX_show_heap (gdb.Command):
state = ''
else:
state = '(free)'
- print ' {} {} {}'.format(allocnode.address + 8, self._node_size(allocnode), state)
+ print ' {} {} {}'.format(allocnode.address + self._allocnodesize,
+ self._node_size(allocnode), state)
cursor += self._node_size(allocnode) / self._allocnodesize
def invoke(self, args, from_tty):
diff --git a/Documentation/rc_mode_switch.odg b/Documentation/rc_mode_switch.odg
index 29d738c39c..682c63e471 100644
Binary files a/Documentation/rc_mode_switch.odg and b/Documentation/rc_mode_switch.odg differ
diff --git a/Documentation/rc_mode_switch.pdf b/Documentation/rc_mode_switch.pdf
index 856dd55c59..e795f48705 100644
Binary files a/Documentation/rc_mode_switch.pdf and b/Documentation/rc_mode_switch.pdf differ
diff --git a/Images/aerocore.prototype b/Images/aerocore.prototype
new file mode 100644
index 0000000000..8502a08646
--- /dev/null
+++ b/Images/aerocore.prototype
@@ -0,0 +1,12 @@
+{
+ "board_id": 19,
+ "magic": "AeroCore",
+ "description": "Firmware for the Gumstix AeroCore board",
+ "image": "",
+ "build_time": 0,
+ "summary": "AEROCORE",
+ "version": "0.1",
+ "image_size": 0,
+ "git_identity": "",
+ "board_revision": 0
+}
diff --git a/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
index 36194ad682..d114fe21a2 100644
--- a/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
+++ b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
@@ -7,7 +7,7 @@
sh /etc/init.d/rc.fw_defaults
-echo "HIL Rascal 110 starting.."
+echo "X Plane HIL starting.."
set HIL yes
diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
index d691a6f2e6..f11aa704eb 100644
--- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
@@ -10,11 +10,11 @@ sh /etc/init.d/rc.mc_defaults
if [ $DO_AUTOCONFIG == yes ]
then
# TODO tune roll/pitch separately
- param set MC_ROLL_P 9.0
+ param set MC_ROLL_P 7.0
param set MC_ROLLRATE_P 0.13
param set MC_ROLLRATE_I 0.0
param set MC_ROLLRATE_D 0.004
- param set MC_PITCH_P 9.0
+ param set MC_PITCH_P 7.0
param set MC_PITCHRATE_P 0.13
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.004
diff --git a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
new file mode 100644
index 0000000000..6179855f6a
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
@@ -0,0 +1,35 @@
+#!nsh
+#
+# Steadidrone QU4D
+#
+# Thomas Gubler
+# Lorenz Meier
+#
+
+sh /etc/init.d/rc.mc_defaults
+
+if [ $DO_AUTOCONFIG == yes ]
+then
+ # TODO tune roll/pitch separately
+ param set MC_ROLL_P 7.0
+ param set MC_ROLLRATE_P 0.13
+ param set MC_ROLLRATE_I 0.0
+ param set MC_ROLLRATE_D 0.004
+ param set MC_PITCH_P 7.0
+ param set MC_PITCHRATE_P 0.13
+ param set MC_PITCHRATE_I 0.0
+ param set MC_PITCHRATE_D 0.004
+ param set MC_YAW_P 0.5
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_D 0.0
+
+ param set BAT_N_CELLS 4
+fi
+
+set MIXER FMU_quad_w
+
+set PWM_MIN 1210
+set PWM_MAX 2100
+
+set PWM_OUTPUTS 1234
diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
index b98ab47748..df2e609bc8 100644
--- a/ROMFS/px4fmu_common/init.d/11001_hexa_cox
+++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
@@ -2,14 +2,14 @@
#
# UNTESTED UNTESTED!
#
-# Generic 10” Hexa coaxial geometry
+# Generic 10" Hexa coaxial geometry
#
# Lorenz Meier
#
sh /etc/init.d/rc.mc_defaults
-set MIXER hexa_cox
+set MIXER FMU_hexa_cox
# We only can run one channel group with one rate, so set all 8 channels
set PWM_OUTPUTS 12345678
diff --git a/ROMFS/px4fmu_common/init.d/12001_octo_cox b/ROMFS/px4fmu_common/init.d/12001_octo_cox
index 655cb6226e..8703f5f2fe 100644
--- a/ROMFS/px4fmu_common/init.d/12001_octo_cox
+++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox
@@ -1,12 +1,12 @@
#!nsh
#
-# Generic 10” Octo coaxial geometry
+# Generic 10" Octo coaxial geometry
#
# Lorenz Meier
#
sh /etc/init.d/rc.mc_defaults
-set MIXER octo_cox
+set MIXER FMU_octo_cox
set PWM_OUTPUTS 12345678
diff --git a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
index 465a22c53a..db0e40fc2e 100644
--- a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
+++ b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
@@ -5,4 +5,4 @@
sh /etc/init.d/rc.fw_defaults
-set MIXER FMU_RET
+set MIXER easystar.mix
diff --git a/ROMFS/px4fmu_common/init.d/2103_skyhunter_1800 b/ROMFS/px4fmu_common/init.d/2103_skyhunter_1800
new file mode 100644
index 0000000000..9bc0262d83
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/2103_skyhunter_1800
@@ -0,0 +1,5 @@
+#!nsh
+
+sh /etc/init.d/rc.fw_defaults
+
+set MIXER FMU_AET
diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom
index a3004d1e13..24372bddcf 100644
--- a/ROMFS/px4fmu_common/init.d/3031_phantom
+++ b/ROMFS/px4fmu_common/init.d/3031_phantom
@@ -2,9 +2,38 @@
#
# Phantom FPV Flying Wing
#
-# Simon Wilks
+# Simon Wilks , Thomas Gubler
#
sh /etc/init.d/rc.fw_defaults
+if [ $DO_AUTOCONFIG == yes ]
+then
+ param set FW_AIRSPD_MIN 13
+ param set FW_AIRSPD_TRIM 15
+ param set FW_AIRSPD_MAX 25
+ param set FW_ATT_TC 0.3
+ param set FW_L1_DAMPING 0.75
+ param set FW_L1_PERIOD 15
+ param set FW_PR_FF 0.2
+ param set FW_PR_I 0.005
+ param set FW_PR_IMAX 0.2
+ param set FW_PR_P 0.03
+ param set FW_P_LIM_MAX 50
+ param set FW_P_LIM_MIN -50
+ param set FW_P_RMAX_NEG 0
+ param set FW_P_RMAX_POS 0
+ param set FW_P_ROLLFF 1
+ param set FW_RR_FF 0.5
+ param set FW_RR_I 0.02
+ param set FW_RR_IMAX 0.2
+ param set FW_RR_P 0.08
+ param set FW_R_LIM 50
+ param set FW_R_RMAX 0
+ param set FW_T_HRATE_P 0.01
+ param set FW_T_RLL2THR 15
+ param set FW_T_SRATE_P 0.01
+ param set FW_T_TIME_CONST 5
+fi
+
set MIXER FMU_Q
diff --git a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5
index bf5a87068f..465166f253 100644
--- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5
+++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5
@@ -23,7 +23,7 @@ then
param set FW_P_LIM_MIN -45
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
- param set FW_P_ROLLFF 0
+ param set FW_P_ROLLFF 1
param set FW_RR_FF 0.3
param set FW_RR_I 0
param set FW_RR_IMAX 0.2
diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing
index 2af3618d98..fff4b58df4 100644
--- a/ROMFS/px4fmu_common/init.d/3033_wingwing
+++ b/ROMFS/px4fmu_common/init.d/3033_wingwing
@@ -7,4 +7,32 @@
sh /etc/init.d/rc.fw_defaults
+if [ $DO_AUTOCONFIG == yes ]
+then
+ param set BAT_N_CELLS 2
+ param set FW_AIRSPD_MAX 15
+ param set FW_AIRSPD_MIN 7
+ param set FW_AIRSPD_TRIM 11
+ param set FW_ATT_TC 0.3
+ param set FW_L1_DAMPING 0.74
+ param set FW_L1_PERIOD 12
+ param set FW_LND_ANG 15
+ param set FW_LND_FLALT 5
+ param set FW_LND_HHDIST 15
+ param set FW_LND_HVIRT 13
+ param set FW_LND_TLALT 5
+ param set FW_THR_LND_MAX 0
+ param set FW_P_ROLLFF 2
+ param set FW_PR_FF 0.6
+ param set FW_PR_IMAX 0.2
+ param set FW_PR_P 0.06
+ param set FW_RR_FF 0.6
+ param set FW_RR_IMAX 0.2
+ param set FW_RR_P 0.09
+ param set FW_THR_CRUISE 0.65
+fi
+
set MIXER FMU_Q
+# Provide ESC a constant 1000 us pulse
+set PWM_OUTPUTS 4
+set PWM_DISARMED 1000
diff --git a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha
new file mode 100644
index 0000000000..7dbda54d3a
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha
@@ -0,0 +1,42 @@
+#!nsh
+#
+# TBS Caipirinha Flying Wing
+#
+# Thomas Gubler
+#
+
+sh /etc/init.d/rc.fw_defaults
+
+if [ $DO_AUTOCONFIG == yes ]
+then
+
+ # TODO: these are the X5 default parameters, update them to the caipi
+
+ param set FW_AIRSPD_MIN 15
+ param set FW_AIRSPD_TRIM 20
+ param set FW_AIRSPD_MAX 40
+ param set FW_ATT_TC 0.3
+ param set FW_L1_DAMPING 0.74
+ param set FW_L1_PERIOD 15
+ param set FW_PR_FF 0.3
+ param set FW_PR_I 0
+ param set FW_PR_IMAX 0.2
+ param set FW_PR_P 0.03
+ param set FW_P_LIM_MAX 45
+ param set FW_P_LIM_MIN -45
+ param set FW_P_RMAX_NEG 0
+ param set FW_P_RMAX_POS 0
+ param set FW_P_ROLLFF 0
+ param set FW_RR_FF 0.3
+ param set FW_RR_I 0
+ param set FW_RR_IMAX 0.2
+ param set FW_RR_P 0.03
+ param set FW_R_LIM 60
+ param set FW_R_RMAX 0
+ param set FW_T_HRATE_P 0.01
+ param set FW_T_RLL2THR 15
+ param set FW_T_SRATE_P 0.01
+ param set FW_T_TIME_CONST 5
+fi
+
+set MIXER FMU_Q
diff --git a/ROMFS/px4fmu_common/init.d/4001_quad_x b/ROMFS/px4fmu_common/init.d/4001_quad_x
index 345b0e3e4e..06c54a41db 100644
--- a/ROMFS/px4fmu_common/init.d/4001_quad_x
+++ b/ROMFS/px4fmu_common/init.d/4001_quad_x
@@ -1,6 +1,6 @@
#!nsh
#
-# Generic 10” Quad X geometry
+# Generic 10" Quad X geometry
#
# Lorenz Meier
#
diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone
index 0f98f7b6c2..14786f2106 100644
--- a/ROMFS/px4fmu_common/init.d/4008_ardrone
+++ b/ROMFS/px4fmu_common/init.d/4008_ardrone
@@ -23,13 +23,15 @@ then
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.0
param set MC_YAW_P 1.0
- param set MC_YAW_D 0.1
param set MC_YAWRATE_P 0.15
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
param set MC_YAW_FF 0.15
+ param set BAT_V_SCALING 0.00838095238
fi
set OUTPUT_MODE ardrone
set USE_IO no
set MIXER skip
+# set MAV_TYPE because no specific mixer is set
+set MAV_TYPE 2
diff --git a/ROMFS/px4fmu_common/init.d/5001_quad_+ b/ROMFS/px4fmu_common/init.d/5001_quad_+
index 55b31067d1..1fb25e5d88 100644
--- a/ROMFS/px4fmu_common/init.d/5001_quad_+
+++ b/ROMFS/px4fmu_common/init.d/5001_quad_+
@@ -1,6 +1,6 @@
#!nsh
#
-# Generic 10” Quad + geometry
+# Generic 10" Quad + geometry
#
# Anton Babushkin
#
diff --git a/ROMFS/px4fmu_common/init.d/6001_hexa_x b/ROMFS/px4fmu_common/init.d/6001_hexa_x
index 7714a508cf..34fc6523fe 100644
--- a/ROMFS/px4fmu_common/init.d/6001_hexa_x
+++ b/ROMFS/px4fmu_common/init.d/6001_hexa_x
@@ -1,6 +1,6 @@
#!nsh
#
-# Generic 10” Hexa X geometry
+# Generic 10" Hexa X geometry
#
# Anton Babushkin
#
diff --git a/ROMFS/px4fmu_common/init.d/7001_hexa_+ b/ROMFS/px4fmu_common/init.d/7001_hexa_+
index 60db8c0690..235e376a6e 100644
--- a/ROMFS/px4fmu_common/init.d/7001_hexa_+
+++ b/ROMFS/px4fmu_common/init.d/7001_hexa_+
@@ -1,6 +1,6 @@
#!nsh
#
-# Generic 10” Hexa + geometry
+# Generic 10" Hexa + geometry
#
# Anton Babushkin
#
diff --git a/ROMFS/px4fmu_common/init.d/8001_octo_x b/ROMFS/px4fmu_common/init.d/8001_octo_x
index 411aee1140..769217dc78 100644
--- a/ROMFS/px4fmu_common/init.d/8001_octo_x
+++ b/ROMFS/px4fmu_common/init.d/8001_octo_x
@@ -1,6 +1,6 @@
#!nsh
#
-# Generic 10” Octo X geometry
+# Generic 10" Octo X geometry
#
# Anton Babushkin
#
diff --git a/ROMFS/px4fmu_common/init.d/9001_octo_+ b/ROMFS/px4fmu_common/init.d/9001_octo_+
index 81132fd3e7..28b074a545 100644
--- a/ROMFS/px4fmu_common/init.d/9001_octo_+
+++ b/ROMFS/px4fmu_common/init.d/9001_octo_+
@@ -1,6 +1,6 @@
#!nsh
#
-# Generic 10” Octo + geometry
+# Generic 10" Octo + geometry
#
# Anton Babushkin
#
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index 7aaf7133ef..b365bd6420 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -68,6 +68,12 @@ then
set MODE custom
fi
+if param compare SYS_AUTOSTART 2103 103
+then
+ sh /etc/init.d/2103_skyhunter_1800
+ set MODE custom
+fi
+
#
# Flying wing
#
@@ -97,6 +103,11 @@ then
sh /etc/init.d/3034_fx79
fi
+if param compare SYS_AUTOSTART 3100
+then
+ sh /etc/init.d/3100_tbs_caipirinha
+fi
+
#
# Quad X
#
@@ -184,6 +195,11 @@ then
sh /etc/init.d/10016_3dr_iris
fi
+if param compare SYS_AUTOSTART 10017
+then
+ sh /etc/init.d/10017_steadidrone_qu4d
+fi
+
#
# Hexa Coaxial
#
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps
index 72327c554e..9aca3fc5f4 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_apps
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps
@@ -3,6 +3,13 @@
# Standard apps for fixed wing
#
-att_pos_estimator_ekf start
+#
+# Start the attitude and position estimator
+#
+ekf_att_pos_estimator start
+
+#
+# Start attitude controller
+#
fw_att_control start
fw_pos_control_l1 start
diff --git a/ROMFS/px4fmu_common/init.d/rc.io b/ROMFS/px4fmu_common/init.d/rc.io
index 6e8fdbc0f7..e23aebd87f 100644
--- a/ROMFS/px4fmu_common/init.d/rc.io
+++ b/ROMFS/px4fmu_common/init.d/rc.io
@@ -11,7 +11,7 @@ px4io recovery
# Adjust PX4IO update rate limit
#
set PX4IO_LIMIT 400
-if hw_ver compare PX4FMU_V1
+if ver hwcmp PX4FMU_V1
then
set PX4IO_LIMIT 200
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index c5aef8273c..517e073afb 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -5,10 +5,10 @@
if [ -d /fs/microsd ]
then
- if hw_ver compare PX4FMU_V1
+ if ver hwcmp PX4FMU_V1
then
echo "Start sdlog2 at 50Hz"
- sdlog2 start -r 50 -a -b 8 -t
+ sdlog2 start -r 50 -a -b 4 -t
else
echo "Start sdlog2 at 200Hz"
sdlog2 start -r 200 -a -b 16 -t
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_apps b/ROMFS/px4fmu_common/init.d/rc.mc_apps
index ed3939757a..268eb9bba0 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_apps
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_apps
@@ -5,6 +5,7 @@
#
attitude_estimator_ekf start
+#ekf_att_pos_estimator start
position_estimator_inav start
mc_att_control start
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
index 4db62607a9..b6b0a5b4ed 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -32,9 +32,15 @@ then
param set MPC_Z_VEL_D 0.0
param set MPC_Z_VEL_MAX 3
param set MPC_Z_FF 0.5
- param set MPC_TILT_MAX 1.0
+ param set MPC_TILTMAX_AIR 45.0
+ param set MPC_TILTMAX_LND 15.0
param set MPC_LAND_SPEED 1.0
- param set MPC_LAND_TILT 0.3
+
+ param set PE_VELNE_NOISE 0.5
+ param set PE_VELNE_NOISE 0.7
+ param set PE_POSNE_NOISE 0.5
+ param set PE_POSD_NOISE 1.0
+
fi
set PWM_RATE 400
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index 235be24316..1e14930fe3 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -22,7 +22,7 @@ then
echo "[init] Using L3GD20(H)"
fi
-if hw_ver compare PX4FMU_V2
+if ver hwcmp PX4FMU_V2
then
if lsm303d start
then
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index 0cd8a0e042..76593881db 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -3,40 +3,20 @@
# USB MAVLink start
#
-echo "Starting MAVLink on this USB console"
-
-# Stop tone alarm
-tone_alarm stop
-
-#
-# Check for UORB
-#
-if uorb start
-then
- echo "uORB started"
-fi
-
-# Tell MAVLink that this link is "fast"
-if mavlink stop
-then
- echo "stopped other MAVLink instance"
-fi
-mavlink start -b 230400 -d /dev/ttyACM0
-
-# Stop commander
-if commander stop
-then
- echo "Commander stopped"
-fi
-sleep 1
-
-# Start the commander
-if commander start
-then
- echo "Commander started"
-fi
-
-echo "MAVLink started, exiting shell.."
+mavlink start -r 10000 -d /dev/ttyACM0
+# Enable a number of interesting streams we want via USB
+mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
+usleep 100000
+mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10
+usleep 100000
+mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20
+usleep 100000
+mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20
+usleep 100000
+mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30
+usleep 100000
+mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
+usleep 100000
# Exit shell to make it available to MAVLink
-exit
+exit
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 57299d7724..8c413e0878 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -20,7 +20,7 @@ echo "[init] Looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
set LOG_FILE /fs/microsd/bootlog.txt
- echo "[init] microSD card mounted at /fs/microsd"
+ echo "[init] microSD mounted: /fs/microsd"
# Start playing the startup tune
tone_alarm start
else
@@ -83,9 +83,9 @@ then
param select $PARAM_FILE
if param load
then
- echo "[init] Parameters loaded: $PARAM_FILE"
+ echo "[init] Params loaded: $PARAM_FILE"
else
- echo "[init] ERROR: Parameters loading failed: $PARAM_FILE"
+ echo "[init] ERROR: Params loading failed: $PARAM_FILE"
fi
#
@@ -108,7 +108,6 @@ then
set HIL no
set VEHICLE_TYPE none
set MIXER none
- set USE_IO yes
set OUTPUT_MODE none
set PWM_OUTPUTS none
set PWM_RATE none
@@ -117,7 +116,12 @@ then
set PWM_MAX none
set MKBLCTRL_MODE none
set FMU_MODE pwm
+ set MAVLINK_FLAGS default
+ set EXIT_ON_END no
set MAV_TYPE none
+ set LOAD_DEFAULT_APPS yes
+ set GPS yes
+ set GPS_FAKE no
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
@@ -128,13 +132,23 @@ then
else
set DO_AUTOCONFIG no
fi
+
+ #
+ # Set USE_IO flag
+ #
+ if param compare SYS_USE_IO 1
+ then
+ set USE_IO yes
+ else
+ set USE_IO no
+ fi
#
# Set parameters and env variables for selected AUTOSTART
#
if param compare SYS_AUTOSTART 0
then
- echo "[init] Don't try to find autostart script"
+ echo "[init] No autostart"
else
sh /etc/init.d/rc.autostart
fi
@@ -144,10 +158,10 @@ then
#
if [ -f $CONFIG_FILE ]
then
- echo "[init] Reading config: $CONFIG_FILE"
+ echo "[init] Config: $CONFIG_FILE"
sh $CONFIG_FILE
else
- echo "[init] Config file not found: $CONFIG_FILE"
+ echo "[init] Config not found: $CONFIG_FILE"
fi
#
@@ -234,7 +248,7 @@ then
echo "[init] ERROR: PX4IO not found, disabling output"
# Avoid using ttyS0 for MAVLink on FMUv1
- if hw_ver compare PX4FMU_V1
+ if ver hwcmp PX4FMU_V1
then
set FMU_MODE serial
fi
@@ -248,14 +262,14 @@ then
if [ $HIL == yes ]
then
set OUTPUT_MODE hil
- if hw_ver compare PX4FMU_V1
+ if ver hwcmp PX4FMU_V1
then
set FMU_MODE serial
fi
- else
- # Try to get an USB console if not in HIL mode
- nshterm /dev/ttyACM0 &
fi
+
+ # Try to get an USB console
+ nshterm /dev/ttyACM0 &
#
# Start the Commander (needs to be this early for in-air-restarts)
@@ -282,6 +296,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
+
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
then
echo "[init] Use FMU as primary output"
@@ -293,7 +308,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
- if hw_ver compare PX4FMU_V1
+ if ver hwcmp PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
then
@@ -305,6 +320,7 @@ then
fi
fi
fi
+
if [ $OUTPUT_MODE == mkblctrl ]
then
echo "[init] Use MKBLCTRL as primary output"
@@ -326,7 +342,8 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
- fi
+ fi
+
if [ $OUTPUT_MODE == hil ]
then
echo "[init] Use HIL as primary output"
@@ -366,7 +383,7 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
- if hw_ver compare PX4FMU_V1
+ if ver hwcmp PX4FMU_V1
then
if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
then
@@ -384,54 +401,47 @@ then
#
# MAVLink
#
- set EXIT_ON_END no
-
- if [ $HIL == yes ]
+ if [ $MAVLINK_FLAGS == default ]
then
- sleep 1
- mavlink start -b 230400 -d /dev/ttyACM0
- usleep 5000
- else
+ # Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
if [ $TTYS1_BUSY == yes ]
then
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
- mavlink start -d /dev/ttyS0
- usleep 5000
-
+ set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0"
+
# Exit from nsh to free port for mavlink
set EXIT_ON_END yes
else
# Start MAVLink on default port: ttyS1
- mavlink start
- usleep 5000
+ set MAVLINK_FLAGS "-r 1000"
fi
fi
-
- #
- # Start the datamanager
- #
- dataman start
-
- #
- # Start the navigator
- #
- navigator start
+
+ mavlink start $MAVLINK_FLAGS
#
# Sensors, Logging, GPS
#
- echo "[init] Start sensors"
sh /etc/init.d/rc.sensors
if [ $HIL == no ]
then
echo "[init] Start logging"
sh /etc/init.d/rc.logging
-
- echo "[init] Start GPS"
- gps start
fi
+ if [ $GPS == yes ]
+ then
+ echo "[init] Start GPS"
+ if [ $GPS_FAKE == yes ]
+ then
+ echo "[init] Faking GPS"
+ gps start -f
+ else
+ gps start
+ fi
+ fi
+
#
# Start up ARDrone Motor interface
#
@@ -465,7 +475,10 @@ then
sh /etc/init.d/rc.interface
# Start standard fixedwing apps
- sh /etc/init.d/rc.fw_apps
+ if [ $LOAD_DEFAULT_APPS == yes ]
+ then
+ sh /etc/init.d/rc.fw_apps
+ fi
fi
#
@@ -495,7 +508,7 @@ then
then
set MAV_TYPE 13
fi
- if [ $MIXER == hexa_cox ]
+ if [ $MIXER == FMU_hexa_cox ]
then
set MAV_TYPE 13
fi
@@ -521,9 +534,22 @@ then
sh /etc/init.d/rc.interface
# Start standard multicopter apps
- sh /etc/init.d/rc.mc_apps
+ if [ $LOAD_DEFAULT_APPS == yes ]
+ then
+ sh /etc/init.d/rc.mc_apps
+ fi
fi
+ #
+ # Start the datamanager
+ #
+ dataman start
+
+ #
+ # Start the navigator
+ #
+ navigator start
+
#
# Generic setup (autostart ID not found)
#
@@ -539,11 +565,12 @@ then
echo "[init] Starting addons script: $EXTRAS_FILE"
sh $EXTRAS_FILE
else
- echo "[init] Addons script not found: $EXTRAS_FILE"
+ echo "[init] No addons script: $EXTRAS_FILE"
fi
if [ $EXIT_ON_END == yes ]
then
+ echo "[init] Exit from nsh"
exit
fi
diff --git a/ROMFS/px4fmu_common/mixers/hexa_cox.mix b/ROMFS/px4fmu_common/mixers/FMU_hexa_cox.mix
similarity index 100%
rename from ROMFS/px4fmu_common/mixers/hexa_cox.mix
rename to ROMFS/px4fmu_common/mixers/FMU_hexa_cox.mix
diff --git a/ROMFS/px4fmu_common/mixers/easystar.mix b/ROMFS/px4fmu_common/mixers/easystar.mix
new file mode 100644
index 0000000000..0051ffdbba
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/easystar.mix
@@ -0,0 +1,31 @@
+EASYSTAR / EASYSTAR II MIXER
+============================
+
+Aileron mixer
+-------------
+One output - would be easy to add support for 2 servos
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 0 10000 10000 0 -10000 10000
+
+Elevator mixer
+------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 1 -10000 -10000 0 -10000 10000
+
+Rudder mixer
+------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 2 -10000 -10000 0 -10000 10000
+
+Motor speed mixer
+-----------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
diff --git a/Tools/.gitignore b/Tools/.gitignore
new file mode 100644
index 0000000000..7628bda821
--- /dev/null
+++ b/Tools/.gitignore
@@ -0,0 +1,2 @@
+parameters.wiki
+parameters.xml
diff --git a/Tools/fetch_log.py b/Tools/fetch_log.py
new file mode 100644
index 0000000000..edcc6557c2
--- /dev/null
+++ b/Tools/fetch_log.py
@@ -0,0 +1,133 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (C) 2012, 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Log fetcher
+#
+# Print list of logs:
+# python fetch_log.py
+#
+# Fetch log:
+# python fetch_log.py sess001/log001.bin
+#
+
+import serial, time, sys, os
+
+def wait_for_string(ser, s, timeout=1.0, debug=False):
+ t0 = time.time()
+ buf = []
+ res = []
+ n = 0
+ while (True):
+ c = ser.read()
+ if debug:
+ sys.stderr.write(c)
+ buf.append(c)
+ if len(buf) > len(s):
+ res.append(buf.pop(0))
+ n += 1
+ if n % 10000 == 0:
+ sys.stderr.write(str(n) + "\n")
+ if "".join(buf) == s:
+ break
+ if timeout > 0.0 and time.time() - t0 > timeout:
+ raise Exception("Timeout while waiting for: " + s)
+ return "".join(res)
+
+def exec_cmd(ser, cmd, timeout):
+ ser.write(cmd + "\n")
+ ser.flush()
+ wait_for_string(ser, cmd + "\r\n", timeout)
+ return wait_for_string(ser, "nsh> \x1b[K", timeout)
+
+def ls_dir(ser, dir, timeout=1.0):
+ res = []
+ for line in exec_cmd(ser, "ls -l " + dir, timeout).splitlines()[1:]:
+ res.append((line[20:], int(line[11:19].strip()), line[1] == "d"))
+ return res
+
+def list_logs(ser):
+ logs_dir = "/fs/microsd/log"
+ res = []
+ for d in ls_dir(ser, logs_dir):
+ if d[2]:
+ sess_dir = d[0][:-1]
+ for f in ls_dir(ser, logs_dir + "/" + sess_dir):
+ log_file = f[0]
+ log_size = f[1]
+ res.append(sess_dir + "/" + log_file + "\t" + str(log_size))
+ return "\n".join(res)
+
+def fetch_log(ser, fn, timeout):
+ cmd = "dumpfile " + fn
+ ser.write(cmd + "\n")
+ ser.flush()
+ wait_for_string(ser, cmd + "\r\n", timeout, True)
+ res = wait_for_string(ser, "\n", timeout, True)
+ data = []
+ if res.startswith("OK"):
+ size = int(res.split()[1])
+ n = 0
+ print "Reading data:"
+ while (n < size):
+ buf = ser.read(min(size - n, 8192))
+ data.append(buf)
+ n += len(buf)
+ sys.stdout.write(".")
+ sys.stdout.flush()
+ print
+ else:
+ raise Exception("Error reading log")
+ wait_for_string(ser, "nsh> \x1b[K", timeout)
+ return "".join(data)
+
+def main():
+ dev = "/dev/tty.usbmodem1"
+ ser = serial.Serial(dev, "115200", timeout=0.2)
+ if len(sys.argv) < 2:
+ print list_logs(ser)
+ else:
+ log_file = sys.argv[1]
+ data = fetch_log(ser, "/fs/microsd/log/" + log_file, 1.0)
+ try:
+ os.mkdir(log_file.split("/")[0])
+ except:
+ pass
+ fout = open(log_file, "wb")
+ fout.write(data)
+ fout.close()
+ ser.close()
+
+if __name__ == "__main__":
+ main()
diff --git a/Tools/fix_code_style.sh b/Tools/fix_code_style.sh
index 0b6743013f..5995d428ea 100755
--- a/Tools/fix_code_style.sh
+++ b/Tools/fix_code_style.sh
@@ -16,5 +16,6 @@ astyle \
--ignore-exclude-errors-x \
--lineend=linux \
--exclude=EASTL \
- --add-brackets \
+ --add-brackets \
+ --max-code-length=120 \
$*
diff --git a/Tools/px4params/.gitignore b/Tools/px4params/.gitignore
deleted file mode 100644
index d78b71a6e8..0000000000
--- a/Tools/px4params/.gitignore
+++ /dev/null
@@ -1,4 +0,0 @@
-parameters.wiki
-parameters.xml
-parameters.wikirpc.xml
-cookies.txt
\ No newline at end of file
diff --git a/Tools/px4params/README.md b/Tools/px4params/README.md
index a23b447995..50dcd2e296 100644
--- a/Tools/px4params/README.md
+++ b/Tools/px4params/README.md
@@ -1,9 +1 @@
-h1. PX4 Parameters Processor
-
-It's designed to scan PX4 source codes, find declarations of tunable parameters,
-and generate the list in various formats.
-
-Currently supported formats are:
-
-* XML for the parametric UI generator
-* Human-readable description in DokuWiki format
+This folder contains a python library used by px_process_params.py
diff --git a/Tools/px4params/__init__.py b/Tools/px4params/__init__.py
new file mode 100644
index 0000000000..3a9f1e2c6d
--- /dev/null
+++ b/Tools/px4params/__init__.py
@@ -0,0 +1 @@
+__all__ = ["srcscanner", "srcparser", "xmlout", "dokuwikiout", "dokuwikirpc"]
\ No newline at end of file
diff --git a/Tools/px4params/dokuwikiout.py b/Tools/px4params/dokuwikiout.py
new file mode 100644
index 0000000000..77e0ef53db
--- /dev/null
+++ b/Tools/px4params/dokuwikiout.py
@@ -0,0 +1,44 @@
+from xml.sax.saxutils import escape
+import codecs
+
+class DokuWikiTablesOutput():
+ def __init__(self, groups):
+ result = ("====== Parameter Reference ======\n"
+ "**This list is auto-generated from the source code** and contains the most recent parameter documentation.\n"
+ "\n")
+ for group in groups:
+ result += "==== %s ====\n\n" % group.GetName()
+ result += "|< 100% 25% 45% 10% 10% 10% >|\n"
+ result += "^ Name ^ Description ^ Min ^ Max ^ Default ^\n"
+ result += "^ ::: ^ Comment ^^^^\n"
+ for param in group.GetParams():
+ code = param.GetFieldValue("code")
+ name = param.GetFieldValue("short_desc")
+ min_val = param.GetFieldValue("min")
+ max_val = param.GetFieldValue("max")
+ def_val = param.GetFieldValue("default")
+ long_desc = param.GetFieldValue("long_desc")
+
+ if name == code:
+ name = ""
+ else:
+ name = name.replace("\n", " ")
+ name = name.replace("|", "%%|%%")
+ name = name.replace("^", "%%^%%")
+
+ result += "| **%s** |" % code
+ result += " %s |" % name
+ result += " %s |" % (min_val or "")
+ result += " %s |" % (max_val or "")
+ result += " %s |" % (def_val or "")
+ result += "\n"
+
+ if long_desc is not None:
+ result += "| ::: | %s
||||\n" % long_desc
+
+ result += "\n"
+ self.output = result;
+
+ def Save(self, filename):
+ with codecs.open(filename, 'w', 'utf-8') as f:
+ f.write(self.output)
diff --git a/Tools/px4params/dokuwikirpc.py b/Tools/px4params/dokuwikirpc.py
new file mode 100644
index 0000000000..407d306fda
--- /dev/null
+++ b/Tools/px4params/dokuwikirpc.py
@@ -0,0 +1,16 @@
+try:
+ import xmlrpclib
+except ImportError:
+ import xmlrpc.client as xmlrpclib
+
+# See https://www.dokuwiki.org/devel:xmlrpc for a list of available functions!
+# Usage example:
+# xmlrpc = dokuwikirpc.get_xmlrpc(url, username, password)
+# print(xmlrpc.dokuwiki.getVersion())
+
+def get_xmlrpc(url, username, password):
+ #proto, url = url.split("://")
+ #url = proto + "://" + username + ":" + password + "@" + url + "/lib/exe/xmlrpc.php"
+ url += "/lib/exe/xmlrpc.php?u=" + username + "&p=" + password
+
+ return xmlrpclib.ServerProxy(url)
diff --git a/Tools/px4params/output_dokuwiki_listings.py b/Tools/px4params/output_dokuwiki_listings.py
deleted file mode 100644
index 83c50ae15d..0000000000
--- a/Tools/px4params/output_dokuwiki_listings.py
+++ /dev/null
@@ -1,31 +0,0 @@
-import codecs
-
-class DokuWikiListingsOutput():
- def __init__(self, groups):
- result = ""
- for group in groups:
- result += "==== %s ====\n\n" % group.GetName()
- for param in group.GetParams():
- code = param.GetFieldValue("code")
- name = param.GetFieldValue("short_desc")
- if code != name:
- name = "%s (%s)" % (name, code)
- result += "=== %s ===\n\n" % name
- long_desc = param.GetFieldValue("long_desc")
- if long_desc is not None:
- result += "%s\n\n" % long_desc
- min_val = param.GetFieldValue("min")
- if min_val is not None:
- result += "* Minimal value: %s\n" % min_val
- max_val = param.GetFieldValue("max")
- if max_val is not None:
- result += "* Maximal value: %s\n" % max_val
- def_val = param.GetFieldValue("default")
- if def_val is not None:
- result += "* Default value: %s\n" % def_val
- result += "\n"
- self.output = result
-
- def Save(self, filename):
- with codecs.open(filename, 'w', 'utf-8') as f:
- f.write(self.output)
diff --git a/Tools/px4params/output_dokuwiki_tables.py b/Tools/px4params/output_dokuwiki_tables.py
deleted file mode 100644
index aa04304df7..0000000000
--- a/Tools/px4params/output_dokuwiki_tables.py
+++ /dev/null
@@ -1,76 +0,0 @@
-from xml.sax.saxutils import escape
-import codecs
-
-class DokuWikiTablesOutput():
- def __init__(self, groups):
- result = "====== Parameter Reference ======\nThis list is auto-generated every few minutes and contains the most recent parameter names and default values.\n\n"
- for group in groups:
- result += "==== %s ====\n\n" % group.GetName()
- result += "|< 100% 20% 20% 10% 10% 10% 30%>|\n"
- result += "^ Name ^ Description ^ Min ^ Max ^ Default ^ Comment ^\n"
- for param in group.GetParams():
- code = param.GetFieldValue("code")
- name = param.GetFieldValue("short_desc")
- min_val = param.GetFieldValue("min")
- max_val = param.GetFieldValue("max")
- def_val = param.GetFieldValue("default")
- long_desc = param.GetFieldValue("long_desc")
-
- name = name.replace("\n", " ")
- result += "| %s | %s |" % (code, name)
-
- if min_val is not None:
- result += " %s |" % min_val
- else:
- result += " |"
-
- if max_val is not None:
- result += " %s |" % max_val
- else:
- result += " |"
-
- if def_val is not None:
- result += " %s |" % def_val
- else:
- result += " |"
-
- if long_desc is not None:
- long_desc = long_desc.replace("\n", " ")
- result += " %s |" % long_desc
- else:
- result += " |"
-
- result += "\n"
- result += "\n"
- self.output = result;
-
- def Save(self, filename):
- with codecs.open(filename, 'w', 'utf-8') as f:
- f.write(self.output)
-
- def SaveRpc(self, filename):
- with codecs.open(filename, 'w', 'utf-8') as f:
- f.write("""
-
- wiki.putPage
-
-
-
- :firmware:parameters
-
-
-
-
- """)
- f.write(escape(self.output))
- f.write("""
-
-
-
-
- sum
- Updated parameters automagically from code.
-
-
-
-""")
diff --git a/Tools/px4params/srcparser.py b/Tools/px4params/srcparser.py
index 1b2d301108..0a4d21d264 100644
--- a/Tools/px4params/srcparser.py
+++ b/Tools/px4params/srcparser.py
@@ -44,6 +44,7 @@ class Parameter(object):
"default": 6,
"min": 5,
"max": 4,
+ "unit": 3,
# all others == 0 (sorted alphabetically)
}
@@ -71,7 +72,7 @@ class Parameter(object):
"""
return self.fields.get(code)
-class Parser(object):
+class SourceParser(object):
"""
Parses provided data and stores all found parameters internally.
"""
@@ -86,7 +87,7 @@ class Parser(object):
re_is_a_number = re.compile(r'^-?[0-9\.]')
re_remove_dots = re.compile(r'\.+$')
- valid_tags = set(["min", "max", "group"])
+ valid_tags = set(["group", "min", "max", "unit"])
# Order of parameter groups
priority = {
diff --git a/Tools/px4params/scanner.py b/Tools/px4params/srcscanner.py
similarity index 73%
rename from Tools/px4params/scanner.py
rename to Tools/px4params/srcscanner.py
index 8779b7bbf6..d7eca72d72 100644
--- a/Tools/px4params/scanner.py
+++ b/Tools/px4params/srcscanner.py
@@ -2,26 +2,21 @@ import os
import re
import codecs
-class Scanner(object):
+class SourceScanner(object):
"""
Traverses directory tree, reads all source files, and passes their contents
to the Parser.
"""
- re_file_extension = re.compile(r'\.([^\.]+)$')
-
def ScanDir(self, srcdir, parser):
"""
Scans provided path and passes all found contents to the parser using
parser.Parse method.
"""
- extensions = set(parser.GetSupportedExtensions())
+ extensions = tuple(parser.GetSupportedExtensions())
for dirname, dirnames, filenames in os.walk(srcdir):
for filename in filenames:
- m = self.re_file_extension.search(filename)
- if m:
- ext = m.group(1)
- if ext in extensions:
+ if filename.endswith(extensions):
path = os.path.join(dirname, filename)
self.ScanFile(path, parser)
diff --git a/Tools/px4params/output_xml.py b/Tools/px4params/xmlout.py
similarity index 100%
rename from Tools/px4params/output_xml.py
rename to Tools/px4params/xmlout.py
diff --git a/Tools/px4params/xmlrpc.sh b/Tools/px4params/xmlrpc.sh
deleted file mode 100644
index efd177f46a..0000000000
--- a/Tools/px4params/xmlrpc.sh
+++ /dev/null
@@ -1,5 +0,0 @@
-python px_process_params.py
-
-rm cookies.txt
-curl --cookie cookies.txt --cookie-jar cookies.txt --user-agent Mozilla/4.0 --data "u=$XMLRPCUSER&p=$XMLRPCPASS" https://pixhawk.org/start?do=login
-curl -k --cookie cookies.txt -H "Content-Type: application/xml" -X POST --data-binary @parameters.wikirpc.xml "https://pixhawk.org/lib/exe/xmlrpc.php"
diff --git a/Tools/px_process_params.py b/Tools/px_process_params.py
new file mode 100644
index 0000000000..12128a997e
--- /dev/null
+++ b/Tools/px_process_params.py
@@ -0,0 +1,140 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (C) 2013-2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# PX4 paramers processor (main executable file)
+#
+# This tool scans the PX4 source code for declarations of tunable parameters
+# and outputs the list in various formats.
+#
+# Currently supported formats are:
+# * XML for the parametric UI generator
+# * Human-readable description in DokuWiki page format
+#
+# This tool also allows to automatically upload the human-readable version
+# to the DokuWiki installation via XML-RPC.
+#
+
+from __future__ import print_function
+import sys
+import os
+import argparse
+from px4params import srcscanner, srcparser, xmlout, dokuwikiout, dokuwikirpc
+
+def main():
+ # Parse command line arguments
+ parser = argparse.ArgumentParser(description="Process parameter documentation.")
+ parser.add_argument("-s", "--src-path",
+ default="../src",
+ metavar="PATH",
+ help="path to source files to scan for parameters")
+ parser.add_argument("-x", "--xml",
+ nargs='?',
+ const="parameters.xml",
+ metavar="FILENAME",
+ help="Create XML file"
+ " (default FILENAME: parameters.xml)")
+ parser.add_argument("-w", "--wiki",
+ nargs='?',
+ const="parameters.wiki",
+ metavar="FILENAME",
+ help="Create DokuWiki file"
+ " (default FILENAME: parameters.wiki)")
+ parser.add_argument("-u", "--wiki-update",
+ nargs='?',
+ const="firmware:parameters",
+ metavar="PAGENAME",
+ help="Update DokuWiki page"
+ " (default PAGENAME: firmware:parameters)")
+ parser.add_argument("--wiki-url",
+ default="https://pixhawk.org",
+ metavar="URL",
+ help="DokuWiki URL"
+ " (default: https://pixhawk.org)")
+ parser.add_argument("--wiki-user",
+ default=os.environ.get('XMLRPCUSER', None),
+ metavar="USERNAME",
+ help="DokuWiki XML-RPC user name"
+ " (default: $XMLRPCUSER environment variable)")
+ parser.add_argument("--wiki-pass",
+ default=os.environ.get('XMLRPCPASS', None),
+ metavar="PASSWORD",
+ help="DokuWiki XML-RPC user password"
+ " (default: $XMLRPCUSER environment variable)")
+ parser.add_argument("--wiki-summary",
+ metavar="SUMMARY",
+ default="Automagically updated parameter documentation from code.",
+ help="DokuWiki page edit summary")
+ args = parser.parse_args()
+
+ # Check for valid command
+ if not (args.xml or args.wiki or args.wiki_update):
+ print("Error: You need to specify at least one output method!\n")
+ parser.print_usage()
+ sys.exit(1)
+
+ # Initialize source scanner and parser
+ scanner = srcscanner.SourceScanner()
+ parser = srcparser.SourceParser()
+
+ # Scan directories, and parse the files
+ print("Scanning source path " + args.src_path)
+ scanner.ScanDir(args.src_path, parser)
+ param_groups = parser.GetParamGroups()
+
+ # Output to XML file
+ if args.xml:
+ print("Creating XML file " + args.xml)
+ out = xmlout.XMLOutput(param_groups)
+ out.Save(args.xml)
+
+ # Output to DokuWiki tables
+ if args.wiki or args.wiki_update:
+ out = dokuwikiout.DokuWikiTablesOutput(param_groups)
+ if args.wiki:
+ print("Creating wiki file " + args.wiki)
+ out.Save(args.wiki)
+ if args.wiki_update:
+ if args.wiki_user and args.wiki_pass:
+ print("Updating wiki page " + args.wiki_update)
+ xmlrpc = dokuwikirpc.get_xmlrpc(args.wiki_url, args.wiki_user, args.wiki_pass)
+ xmlrpc.wiki.putPage(args.wiki_update, out.output, {'sum': args.wiki_summary})
+ else:
+ print("Error: You need to specify DokuWiki XML-RPC username and password!")
+
+ print("All done!")
+
+
+if __name__ == "__main__":
+ main()
diff --git a/Tools/px_romfs_pruner.py b/Tools/px_romfs_pruner.py
new file mode 100644
index 0000000000..fcc40b09e1
--- /dev/null
+++ b/Tools/px_romfs_pruner.py
@@ -0,0 +1,84 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (C) 2014 PX4 Development Team. All rights reserved.
+# Author: Julian Oes
+
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+
+"""
+px_romfs_pruner.py:
+Delete all comments and newlines before ROMFS is converted to an image
+"""
+
+from __future__ import print_function
+import argparse
+import os
+
+
+def main():
+
+ # Parse commandline arguments
+ parser = argparse.ArgumentParser(description="ROMFS pruner.")
+ parser.add_argument('--folder', action="store", help="ROMFS scratch folder.")
+ args = parser.parse_args()
+
+ print("Pruning ROMFS files.")
+
+ # go through
+ for (root, dirs, files) in os.walk(args.folder):
+ for file in files:
+ # only prune text files
+ if ".zip" in file or ".bin" in file or ".swp" in file:
+ continue
+
+ file_path = os.path.join(root, file)
+
+ # read file line by line
+ pruned_content = ""
+ with open(file_path, "r") as f:
+ for line in f:
+
+ # handle mixer files differently than startup files
+ if file_path.endswith(".mix"):
+ if line.startswith(("Z:", "M:", "R: ", "O:", "S:")):
+ pruned_content += line
+ else:
+ if not line.isspace() and not line.strip().startswith("#"):
+ pruned_content += line
+
+ # overwrite old scratch file
+ with open(file_path, "w") as f:
+ f.write(pruned_content)
+
+
+if __name__ == '__main__':
+ main()
diff --git a/Tools/px_update_wiki.sh b/Tools/px_update_wiki.sh
new file mode 100644
index 0000000000..d66bb9e10b
--- /dev/null
+++ b/Tools/px_update_wiki.sh
@@ -0,0 +1,2 @@
+# Remember to set the XMLRPCUSER and XMLRPCPASS environment variables
+python px_process_params.py --wiki-update
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py
index e4a8b3c054..985e6ffd9d 100755
--- a/Tools/px_uploader.py
+++ b/Tools/px_uploader.py
@@ -389,18 +389,22 @@ class uploader(object):
self.otp_pid = self.otp[12:8:-1]
self.otp_coa = self.otp[32:160]
# show user:
- print("type: " + self.otp_id.decode('Latin-1'))
- print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1'))
- print("vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1'))
- print("pid: "+ binascii.hexlify(self.otp_pid).decode('Latin-1'))
- print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('Latin-1'))
- print("sn: ", end='')
- for byte in range(0,12,4):
- x = self.__getSN(byte)
- x = x[::-1] # reverse the bytes
- self.sn = self.sn + x
- print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
- print('')
+ try:
+ print("type: " + self.otp_id.decode('Latin-1'))
+ print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1'))
+ print("vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1'))
+ print("pid: "+ binascii.hexlify(self.otp_pid).decode('Latin-1'))
+ print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('Latin-1'))
+ print("sn: ", end='')
+ for byte in range(0,12,4):
+ x = self.__getSN(byte)
+ x = x[::-1] # reverse the bytes
+ self.sn = self.sn + x
+ print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
+ print('')
+ except Exception:
+ # ignore bad character encodings
+ pass
print("erase...")
self.__erase()
diff --git a/Tools/tests-host/.gitignore b/Tools/tests-host/.gitignore
index 61e0915515..87b314c614 100644
--- a/Tools/tests-host/.gitignore
+++ b/Tools/tests-host/.gitignore
@@ -1,2 +1,4 @@
./obj/*
mixer_test
+sbus2_test
+autodeclination_test
diff --git a/Tools/tests-host/Makefile b/Tools/tests-host/Makefile
index 7ab1454f01..f0737ef88c 100644
--- a/Tools/tests-host/Makefile
+++ b/Tools/tests-host/Makefile
@@ -1,47 +1,39 @@
CC=g++
-CFLAGS=-I. -I../../src/modules -I ../../src/include -I../../src/drivers -I../../src -D__EXPORT="" -Dnullptr="0"
+CFLAGS=-I. -I../../src/modules -I ../../src/include -I../../src/drivers \
+ -I../../src -I../../src/lib -D__EXPORT="" -Dnullptr="0" -lm
-ODIR=obj
-LDIR =../lib
+all: mixer_test sbus2_test autodeclination_test
-LIBS=-lm
+MIXER_FILES=../../src/systemcmds/tests/test_mixer.cpp \
+ ../../src/systemcmds/tests/test_conv.cpp \
+ ../../src/modules/systemlib/mixer/mixer_simple.cpp \
+ ../../src/modules/systemlib/mixer/mixer_multirotor.cpp \
+ ../../src/modules/systemlib/mixer/mixer.cpp \
+ ../../src/modules/systemlib/mixer/mixer_group.cpp \
+ ../../src/modules/systemlib/mixer/mixer_load.c \
+ ../../src/modules/systemlib/pwm_limit/pwm_limit.c \
+ hrt.cpp \
+ mixer_test.cpp
-#_DEPS = test.h
-#DEPS = $(patsubst %,$(IDIR)/%,$(_DEPS))
+SBUS2_FILES=../../src/modules/px4iofirmware/sbus.c \
+ hrt.cpp \
+ sbus2_test.cpp
-_OBJ = mixer_test.o test_mixer.o mixer_simple.o mixer_multirotor.o \
- mixer.o mixer_group.o mixer_load.o test_conv.o pwm_limit.o hrt.o
-OBJ = $(patsubst %,$(ODIR)/%,$(_OBJ))
+AUTODECLINATION_FILES= ../../src/lib/geo/geo_mag_declination.c \
+ hrt.cpp \
+ autodeclination_test.cpp
-#$(DEPS)
-$(ODIR)/%.o: %.cpp
- mkdir -p obj
- $(CC) -c -o $@ $< $(CFLAGS)
+mixer_test: $(MIXER_FILES)
+ $(CC) -o mixer_test $(MIXER_FILES) $(CFLAGS)
-$(ODIR)/%.o: ../../src/systemcmds/tests/%.cpp
- $(CC) -c -o $@ $< $(CFLAGS)
+sbus2_test: $(SBUS2_FILES)
+ $(CC) -o sbus2_test $(SBUS2_FILES) $(CFLAGS)
-$(ODIR)/%.o: ../../src/modules/systemlib/%.cpp
- $(CC) -c -o $@ $< $(CFLAGS)
-
-$(ODIR)/%.o: ../../src/modules/systemlib/mixer/%.cpp
- $(CC) -c -o $@ $< $(CFLAGS)
-
-$(ODIR)/%.o: ../../src/modules/systemlib/pwm_limit/%.cpp
- $(CC) -c -o $@ $< $(CFLAGS)
-
-$(ODIR)/%.o: ../../src/modules/systemlib/pwm_limit/%.c
- $(CC) -c -o $@ $< $(CFLAGS)
-
-$(ODIR)/%.o: ../../src/modules/systemlib/mixer/%.c
- $(CC) -c -o $@ $< $(CFLAGS)
-
-#
-mixer_test: $(OBJ)
- g++ -o $@ $^ $(CFLAGS) $(LIBS)
+autodeclination_test: $(SBUS2_FILES)
+ $(CC) -o autodeclination_test $(AUTODECLINATION_FILES) $(CFLAGS)
.PHONY: clean
clean:
- rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~
\ No newline at end of file
+ rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~ mixer_test sbus2_test autodeclination_test
\ No newline at end of file
diff --git a/Tools/tests-host/autodeclination_test.cpp b/Tools/tests-host/autodeclination_test.cpp
new file mode 100644
index 0000000000..93bc340bb3
--- /dev/null
+++ b/Tools/tests-host/autodeclination_test.cpp
@@ -0,0 +1,28 @@
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include "../../src/systemcmds/tests/tests.h"
+#include
+
+int main(int argc, char *argv[]) {
+ warnx("autodeclination test started");
+
+ if (argc < 3)
+ errx(1, "Need lat/lon!");
+
+ char* p_end;
+
+ float lat = strtod(argv[1], &p_end);
+ float lon = strtod(argv[2], &p_end);
+
+ float declination = get_mag_declination(lat, lon);
+
+ printf("lat: %f lon: %f, dec: %f\n", lat, lon, declination);
+
+}
diff --git a/Tools/tests-host/board_config.h b/Tools/tests-host/board_config.h
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/Tools/tests-host/debug.h b/Tools/tests-host/debug.h
new file mode 100644
index 0000000000..9824d13fc3
--- /dev/null
+++ b/Tools/tests-host/debug.h
@@ -0,0 +1,5 @@
+
+#pragma once
+
+#include
+#define lowsyslog warnx
\ No newline at end of file
diff --git a/Tools/tests-host/mixer_test.cpp b/Tools/tests-host/mixer_test.cpp
index e311617f96..06499afd0e 100644
--- a/Tools/tests-host/mixer_test.cpp
+++ b/Tools/tests-host/mixer_test.cpp
@@ -11,4 +11,4 @@ int main(int argc, char *argv[]) {
test_mixer(3, args);
test_conv(1, args);
-}
\ No newline at end of file
+}
diff --git a/Tools/tests-host/run_tests.sh b/Tools/tests-host/run_tests.sh
new file mode 100755
index 0000000000..ff5ee509ac
--- /dev/null
+++ b/Tools/tests-host/run_tests.sh
@@ -0,0 +1,6 @@
+#!/bin/sh
+
+make clean
+make all
+./mixer_test
+./sbus2_test ../../../../data/sbus2/sbus2_r7008SB_gps_baro_tx_off.txt
\ No newline at end of file
diff --git a/Tools/tests-host/sbus2_test.cpp b/Tools/tests-host/sbus2_test.cpp
new file mode 100644
index 0000000000..d8fcb695d8
--- /dev/null
+++ b/Tools/tests-host/sbus2_test.cpp
@@ -0,0 +1,75 @@
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include "../../src/systemcmds/tests/tests.h"
+
+int main(int argc, char *argv[]) {
+ warnx("SBUS2 test started");
+
+ if (argc < 2)
+ errx(1, "Need a filename for the input file");
+
+ warnx("loading data from: %s", argv[1]);
+
+ FILE *fp;
+
+ fp = fopen(argv[1],"rt");
+
+ if (!fp)
+ errx(1, "failed opening file");
+
+ float f;
+ unsigned x;
+ int ret;
+
+ // Trash the first 20 lines
+ for (unsigned i = 0; i < 20; i++) {
+ (void)fscanf(fp, "%f,%x,,", &f, &x);
+ }
+
+ // Init the parser
+ uint8_t frame[30];
+ unsigned partial_frame_count = 0;
+ uint16_t rc_values[18];
+ uint16_t num_values;
+ bool sbus_failsafe;
+ bool sbus_frame_drop;
+ uint16_t max_channels = sizeof(rc_values) / sizeof(rc_values[0]);
+
+ float last_time = 0;
+
+ while (EOF != (ret = fscanf(fp, "%f,%x,,", &f, &x))) {
+ if (((f - last_time) * 1000 * 1000) > 3000) {
+ partial_frame_count = 0;
+ warnx("FRAME RESET\n\n");
+ }
+
+ frame[partial_frame_count] = x;
+ partial_frame_count++;
+
+ //warnx("%f: 0x%02x, first: 0x%02x, last: 0x%02x, pcount: %u", (double)f, x, frame[0], frame[24], partial_frame_count);
+
+ if (partial_frame_count == sizeof(frame))
+ partial_frame_count = 0;
+
+ last_time = f;
+
+ // Pipe the data into the parser
+ hrt_abstime now = hrt_absolute_time();
+
+ //if (partial_frame_count % 25 == 0)
+ //sbus_parse(now, frame, &partial_frame_count, rc_values, &num_values, &sbus_failsafe, &sbus_frame_drop, max_channels);
+ }
+
+ if (ret == EOF) {
+ warnx("Test finished, reached end of file");
+ } else {
+ warnx("Test aborted, errno: %d", ret);
+ }
+
+}
diff --git a/makefiles/board_aerocore.mk b/makefiles/board_aerocore.mk
new file mode 100644
index 0000000000..6f4b932666
--- /dev/null
+++ b/makefiles/board_aerocore.mk
@@ -0,0 +1,11 @@
+#
+# Board-specific definitions for the Gumstix AeroCore
+#
+
+#
+# Configure the toolchain
+#
+CONFIG_ARCH = CORTEXM4F
+CONFIG_BOARD = AEROCORE
+
+include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
diff --git a/makefiles/config_aerocore_default.mk b/makefiles/config_aerocore_default.mk
new file mode 100644
index 0000000000..d6902c4ee2
--- /dev/null
+++ b/makefiles/config_aerocore_default.mk
@@ -0,0 +1,125 @@
+#
+# Makefile for the AeroCore *default* configuration
+#
+
+#
+# Use the configuration's ROMFS.
+#
+ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
+
+#
+# Board support modules
+#
+MODULES += drivers/device
+MODULES += drivers/stm32
+MODULES += drivers/stm32/adc
+MODULES += drivers/stm32/tone_alarm
+MODULES += drivers/led
+MODULES += drivers/px4fmu
+MODULES += drivers/boards/aerocore
+MODULES += drivers/lsm303d
+MODULES += drivers/l3gd20
+MODULES += drivers/ms5611
+MODULES += drivers/gps
+MODULES += drivers/hil
+MODULES += modules/sensors
+
+#
+# System commands
+#
+MODULES += systemcmds/boardinfo
+MODULES += systemcmds/mixer
+MODULES += systemcmds/param
+MODULES += systemcmds/perf
+MODULES += systemcmds/preflight_check
+MODULES += systemcmds/pwm
+MODULES += systemcmds/esc_calib
+MODULES += systemcmds/reboot
+MODULES += systemcmds/top
+MODULES += systemcmds/config
+MODULES += systemcmds/nshterm
+MODULES += systemcmds/mtd
+MODULES += systemcmds/dumpfile
+
+#
+# General system control
+#
+MODULES += modules/commander
+MODULES += modules/navigator
+MODULES += modules/mavlink
+
+#
+# Estimation modules (EKF/ SO3 / other filters)
+#
+MODULES += modules/attitude_estimator_ekf
+MODULES += modules/attitude_estimator_so3
+MODULES += modules/ekf_att_pos_estimator
+MODULES += modules/position_estimator_inav
+
+#
+# Vehicle Control
+#
+MODULES += modules/fw_pos_control_l1
+MODULES += modules/fw_att_control
+MODULES += modules/mc_att_control
+MODULES += modules/mc_pos_control
+
+#
+# Library modules
+#
+MODULES += modules/systemlib
+MODULES += modules/systemlib/mixer
+MODULES += modules/controllib
+MODULES += modules/uORB
+MODULES += modules/dataman
+
+#
+# Libraries
+#
+LIBRARIES += lib/mathlib/CMSIS
+MODULES += lib/mathlib
+MODULES += lib/mathlib/math/filter
+MODULES += lib/ecl
+MODULES += lib/external_lgpl
+MODULES += lib/geo
+MODULES += lib/conversion
+MODULES += lib/launchdetection
+
+#
+# Demo apps
+#
+#MODULES += examples/math_demo
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/hello_sky
+MODULES += examples/px4_simple_app
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/daemon
+#MODULES += examples/px4_daemon_app
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/debug_values
+#MODULES += examples/px4_mavlink_debug
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
+#MODULES += examples/fixedwing_control
+
+# Hardware test
+#MODULES += examples/hwtest
+
+#
+# Transitional support - add commands from the NuttX export archive.
+#
+# In general, these should move to modules over time.
+#
+# Each entry here is ... but we use a helper macro
+# to make the table a bit more readable.
+#
+define _B
+ $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
+endef
+
+BUILTIN_COMMANDS := \
+ $(call _B, hello, , 2048, hello_main) \
+ $(call _B, i2c, , 2048, i2c_main)
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index aff614cbb3..810e008aeb 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -55,7 +55,8 @@ MODULES += systemcmds/top
MODULES += systemcmds/tests
MODULES += systemcmds/config
MODULES += systemcmds/nshterm
-MODULES += systemcmds/hw_ver
+MODULES += systemcmds/dumpfile
+MODULES += systemcmds/ver
#
# General system control
@@ -69,7 +70,7 @@ MODULES += modules/gpio_led
# Estimation modules (EKF/ SO3 / other filters)
#
MODULES += modules/attitude_estimator_ekf
-MODULES += modules/att_pos_estimator_ekf
+MODULES += modules/ekf_att_pos_estimator
MODULES += modules/position_estimator_inav
#MODULES += examples/flow_position_estimator
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index 2ad2f63a95..d6e88859c1 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -27,6 +27,7 @@ MODULES += drivers/l3gd20
MODULES += drivers/hmc5883
MODULES += drivers/ms5611
MODULES += drivers/mb12xx
+MODULES += drivers/sf0x
MODULES += drivers/gps
MODULES += drivers/hil
MODULES += drivers/hott/hott_telemetry
@@ -62,7 +63,8 @@ MODULES += systemcmds/tests
MODULES += systemcmds/config
MODULES += systemcmds/nshterm
MODULES += systemcmds/mtd
-MODULES += systemcmds/hw_ver
+MODULES += systemcmds/dumpfile
+MODULES += systemcmds/ver
#
# General system control
@@ -70,14 +72,14 @@ MODULES += systemcmds/hw_ver
MODULES += modules/commander
MODULES += modules/navigator
MODULES += modules/mavlink
-MODULES += modules/mavlink_onboard
+MODULES += modules/gpio_led
#
# Estimation modules (EKF/ SO3 / other filters)
#
MODULES += modules/attitude_estimator_ekf
MODULES += modules/attitude_estimator_so3
-MODULES += modules/att_pos_estimator_ekf
+MODULES += modules/ekf_att_pos_estimator
MODULES += modules/position_estimator_inav
MODULES += examples/flow_position_estimator
diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk
index 79922374d7..84274bf754 100644
--- a/makefiles/config_px4fmu-v2_test.mk
+++ b/makefiles/config_px4fmu-v2_test.mk
@@ -29,7 +29,7 @@ MODULES += systemcmds/reboot
MODULES += systemcmds/tests
MODULES += systemcmds/nshterm
MODULES += systemcmds/mtd
-MODULES += systemcmds/hw_ver
+MODULES += systemcmds/ver
#
# Library modules
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
index cb20d9cd19..60602e76fe 100644
--- a/makefiles/firmware.mk
+++ b/makefiles/firmware.mk
@@ -113,7 +113,7 @@ endif
$(info % GIT_DESC = $(GIT_DESC))
#
-# Set a default target so that included makefiles or errors here don't
+# Set a default target so that included makefiles or errors here don't
# cause confusion.
#
# XXX We could do something cute here with $(DEFAULT_GOAL) if it's not one
@@ -177,7 +177,7 @@ GLOBAL_DEPS += $(MAKEFILE_LIST)
#
# Extra things we should clean
#
-EXTRA_CLEANS =
+EXTRA_CLEANS =
#
@@ -355,6 +355,9 @@ ROMFS_OBJ = $(ROMFS_CSRC:.c=.o)
LIBS += $(ROMFS_OBJ)
LINK_DEPS += $(ROMFS_OBJ)
+# Remove all comments from startup and mixer files
+ROMFS_PRUNER = $(PX4_BASE)/Tools/px_romfs_pruner.py
+
# Turn the ROMFS image into an object file
$(ROMFS_OBJ): $(ROMFS_IMG) $(GLOBAL_DEPS)
$(call BIN_TO_OBJ,$<,$@,romfs_img)
@@ -368,10 +371,13 @@ $(ROMFS_IMG): $(ROMFS_SCRATCH) $(ROMFS_DEPS) $(GLOBAL_DEPS)
$(ROMFS_SCRATCH): $(ROMFS_DEPS) $(GLOBAL_DEPS)
$(Q) $(MKDIR) -p $(ROMFS_SCRATCH)
$(Q) $(COPYDIR) $(ROMFS_ROOT)/* $(ROMFS_SCRATCH)
+# delete all files in ROMFS_SCRATCH which start with a . or end with a ~
+ $(Q) $(RM) $(ROMFS_SCRATCH)/*/.[!.]* $(ROMFS_SCRATCH)/*/*~
ifneq ($(ROMFS_EXTRA_FILES),)
$(Q) $(MKDIR) -p $(ROMFS_SCRATCH)/extras
$(Q) $(COPY) $(ROMFS_EXTRA_FILES) $(ROMFS_SCRATCH)/extras
endif
+ $(Q) $(PYTHON) -u $(ROMFS_PRUNER) --folder $(ROMFS_SCRATCH)
EXTRA_CLEANS += $(ROMGS_OBJ) $(ROMFS_IMG)
diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk
index bb729e1032..b519e0e7a1 100644
--- a/makefiles/toolchain_gnu-arm-eabi.mk
+++ b/makefiles/toolchain_gnu-arm-eabi.mk
@@ -1,5 +1,5 @@
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -125,7 +125,11 @@ ARCHWARNINGS = -Wall \
-Wlogical-op \
-Wmissing-declarations \
-Wpacked \
- -Wno-unused-parameter
+ -Wno-unused-parameter \
+ -Werror=format-security \
+ -Werror=array-bounds \
+ -Wfatal-errors \
+ -Wformat=1
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
@@ -142,7 +146,8 @@ ARCHCWARNINGS = $(ARCHWARNINGS) \
# C++-specific warnings
#
-ARCHWARNINGSXX = $(ARCHWARNINGS)
+ARCHWARNINGSXX = $(ARCHWARNINGS) \
+ -Wno-missing-field-initializers
# pull in *just* libm from the toolchain ... this is grody
LIBM := $(shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a)
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
index 2acb7965ca..c887dc68a1 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
@@ -12,15 +12,15 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 0, 0, 0, 0, 0, 13, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 0, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
+#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 0, 0, 0, 0, 0, 29, 223, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 0, 47, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_AHRS2, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
#include "../protocol.h"
@@ -30,95 +30,6 @@ extern "C" {
// ENUM DEFINITIONS
-/** @brief Enumeration of possible mount operation modes */
-#ifndef HAVE_ENUM_MAV_MOUNT_MODE
-#define HAVE_ENUM_MAV_MOUNT_MODE
-enum MAV_MOUNT_MODE
-{
- MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */
- MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | */
- MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
- MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
- MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
- MAV_MOUNT_MODE_ENUM_END=5, /* | */
-};
-#endif
-
-/** @brief */
-#ifndef HAVE_ENUM_MAV_CMD
-#define HAVE_ENUM_MAV_CMD
-enum MAV_CMD
-{
- MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
- MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
- MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
- MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
- MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
- MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
- MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */
- MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */
- MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
- MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
- MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
- MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
- MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
- MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
- MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
- MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
- MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
- MAV_CMD_ENUM_END=501, /* | */
-};
-#endif
-
-/** @brief */
-#ifndef HAVE_ENUM_FENCE_ACTION
-#define HAVE_ENUM_FENCE_ACTION
-enum FENCE_ACTION
-{
- FENCE_ACTION_NONE=0, /* Disable fenced mode | */
- FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */
- FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */
- FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */
- FENCE_ACTION_ENUM_END=4, /* | */
-};
-#endif
-
-/** @brief */
-#ifndef HAVE_ENUM_FENCE_BREACH
-#define HAVE_ENUM_FENCE_BREACH
-enum FENCE_BREACH
-{
- FENCE_BREACH_NONE=0, /* No last fence breach | */
- FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */
- FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */
- FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */
- FENCE_BREACH_ENUM_END=4, /* | */
-};
-#endif
-
/** @brief */
#ifndef HAVE_ENUM_LIMITS_STATE
#define HAVE_ENUM_LIMITS_STATE
@@ -157,6 +68,18 @@ enum RALLY_FLAGS
};
#endif
+/** @brief */
+#ifndef HAVE_ENUM_PARACHUTE_ACTION
+#define HAVE_ENUM_PARACHUTE_ACTION
+enum PARACHUTE_ACTION
+{
+ PARACHUTE_DISABLE=0, /* Disable parachute release | */
+ PARACHUTE_ENABLE=1, /* Enable parachute release | */
+ PARACHUTE_RELEASE=2, /* Release parachute | */
+ PARACHUTE_ACTION_ENUM_END=3, /* | */
+};
+#endif
+
#include "../common/common.h"
// MAVLINK VERSION
@@ -197,6 +120,7 @@ enum RALLY_FLAGS
#include "./mavlink_msg_airspeed_autocal.h"
#include "./mavlink_msg_rally_point.h"
#include "./mavlink_msg_rally_fetch_point.h"
+#include "./mavlink_msg_compassmot_status.h"
#include "./mavlink_msg_ahrs2.h"
#ifdef __cplusplus
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h
index c3ead11401..50ddc79e5a 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx,
#endif
}
+#if MAVLINK_MSG_ID_AHRS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_ahrs_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, omegaIx);
+ _mav_put_float(buf, 4, omegaIy);
+ _mav_put_float(buf, 8, omegaIz);
+ _mav_put_float(buf, 12, accel_weight);
+ _mav_put_float(buf, 16, renorm_val);
+ _mav_put_float(buf, 20, error_rp);
+ _mav_put_float(buf, 24, error_yaw);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_LEN);
+#endif
+#else
+ mavlink_ahrs_t *packet = (mavlink_ahrs_t *)msgbuf;
+ packet->omegaIx = omegaIx;
+ packet->omegaIy = omegaIy;
+ packet->omegaIz = omegaIz;
+ packet->accel_weight = accel_weight;
+ packet->renorm_val = renorm_val;
+ packet->error_rp = error_rp;
+ packet->error_yaw = error_yaw;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)packet, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)packet, MAVLINK_MSG_ID_AHRS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE AHRS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs2.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs2.h
index f6fde9590c..33e0066882 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs2.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs2.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_ahrs2_send(mavlink_channel_t chan, float roll, fl
#endif
}
+#if MAVLINK_MSG_ID_AHRS2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_ahrs2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_LEN);
+#endif
+#else
+ mavlink_ahrs2_t *packet = (mavlink_ahrs2_t *)msgbuf;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->altitude = altitude;
+ packet->lat = lat;
+ packet->lng = lng;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)packet, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)packet, MAVLINK_MSG_ID_AHRS2_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE AHRS2 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h
index d046f2ad09..521831c8ff 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h
@@ -267,6 +267,60 @@ static inline void mavlink_msg_airspeed_autocal_send(mavlink_channel_t chan, flo
#endif
}
+#if MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_airspeed_autocal_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, vx);
+ _mav_put_float(buf, 4, vy);
+ _mav_put_float(buf, 8, vz);
+ _mav_put_float(buf, 12, diff_pressure);
+ _mav_put_float(buf, 16, EAS2TAS);
+ _mav_put_float(buf, 20, ratio);
+ _mav_put_float(buf, 24, state_x);
+ _mav_put_float(buf, 28, state_y);
+ _mav_put_float(buf, 32, state_z);
+ _mav_put_float(buf, 36, Pax);
+ _mav_put_float(buf, 40, Pby);
+ _mav_put_float(buf, 44, Pcz);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+#else
+ mavlink_airspeed_autocal_t *packet = (mavlink_airspeed_autocal_t *)msgbuf;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->diff_pressure = diff_pressure;
+ packet->EAS2TAS = EAS2TAS;
+ packet->ratio = ratio;
+ packet->state_x = state_x;
+ packet->state_y = state_y;
+ packet->state_z = state_z;
+ packet->Pax = Pax;
+ packet->Pby = Pby;
+ packet->Pcz = Pcz;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE AIRSPEED_AUTOCAL UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h
index 821ce73e47..3c18e644ef 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1
#endif
}
+#if MAVLINK_MSG_ID_AP_ADC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_ap_adc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, adc1);
+ _mav_put_uint16_t(buf, 2, adc2);
+ _mav_put_uint16_t(buf, 4, adc3);
+ _mav_put_uint16_t(buf, 6, adc4);
+ _mav_put_uint16_t(buf, 8, adc5);
+ _mav_put_uint16_t(buf, 10, adc6);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_LEN);
+#endif
+#else
+ mavlink_ap_adc_t *packet = (mavlink_ap_adc_t *)msgbuf;
+ packet->adc1 = adc1;
+ packet->adc2 = adc2;
+ packet->adc3 = adc3;
+ packet->adc4 = adc4;
+ packet->adc5 = adc5;
+ packet->adc6 = adc6;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)packet, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)packet, MAVLINK_MSG_ID_AP_ADC_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE AP_ADC UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_compassmot_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_compassmot_status.h
new file mode 100644
index 0000000000..9655459889
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_compassmot_status.h
@@ -0,0 +1,329 @@
+// MESSAGE COMPASSMOT_STATUS PACKING
+
+#define MAVLINK_MSG_ID_COMPASSMOT_STATUS 177
+
+typedef struct __mavlink_compassmot_status_t
+{
+ float current; ///< current (amps)
+ float CompensationX; ///< Motor Compensation X
+ float CompensationY; ///< Motor Compensation Y
+ float CompensationZ; ///< Motor Compensation Z
+ uint16_t throttle; ///< throttle (percent*10)
+ uint16_t interference; ///< interference (percent)
+} mavlink_compassmot_status_t;
+
+#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN 20
+#define MAVLINK_MSG_ID_177_LEN 20
+
+#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC 240
+#define MAVLINK_MSG_ID_177_CRC 240
+
+
+
+#define MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS { \
+ "COMPASSMOT_STATUS", \
+ 6, \
+ { { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_compassmot_status_t, current) }, \
+ { "CompensationX", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_compassmot_status_t, CompensationX) }, \
+ { "CompensationY", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_compassmot_status_t, CompensationY) }, \
+ { "CompensationZ", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_compassmot_status_t, CompensationZ) }, \
+ { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_compassmot_status_t, throttle) }, \
+ { "interference", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_compassmot_status_t, interference) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a compassmot_status message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param throttle throttle (percent*10)
+ * @param current current (amps)
+ * @param interference interference (percent)
+ * @param CompensationX Motor Compensation X
+ * @param CompensationY Motor Compensation Y
+ * @param CompensationZ Motor Compensation Z
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_compassmot_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
+ _mav_put_float(buf, 0, current);
+ _mav_put_float(buf, 4, CompensationX);
+ _mav_put_float(buf, 8, CompensationY);
+ _mav_put_float(buf, 12, CompensationZ);
+ _mav_put_uint16_t(buf, 16, throttle);
+ _mav_put_uint16_t(buf, 18, interference);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#else
+ mavlink_compassmot_status_t packet;
+ packet.current = current;
+ packet.CompensationX = CompensationX;
+ packet.CompensationY = CompensationY;
+ packet.CompensationZ = CompensationZ;
+ packet.throttle = throttle;
+ packet.interference = interference;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a compassmot_status message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param throttle throttle (percent*10)
+ * @param current current (amps)
+ * @param interference interference (percent)
+ * @param CompensationX Motor Compensation X
+ * @param CompensationY Motor Compensation Y
+ * @param CompensationZ Motor Compensation Z
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_compassmot_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t throttle,float current,uint16_t interference,float CompensationX,float CompensationY,float CompensationZ)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
+ _mav_put_float(buf, 0, current);
+ _mav_put_float(buf, 4, CompensationX);
+ _mav_put_float(buf, 8, CompensationY);
+ _mav_put_float(buf, 12, CompensationZ);
+ _mav_put_uint16_t(buf, 16, throttle);
+ _mav_put_uint16_t(buf, 18, interference);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#else
+ mavlink_compassmot_status_t packet;
+ packet.current = current;
+ packet.CompensationX = CompensationX;
+ packet.CompensationY = CompensationY;
+ packet.CompensationZ = CompensationZ;
+ packet.throttle = throttle;
+ packet.interference = interference;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a compassmot_status struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param compassmot_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_compassmot_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status)
+{
+ return mavlink_msg_compassmot_status_pack(system_id, component_id, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
+}
+
+/**
+ * @brief Encode a compassmot_status struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param compassmot_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_compassmot_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status)
+{
+ return mavlink_msg_compassmot_status_pack_chan(system_id, component_id, chan, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
+}
+
+/**
+ * @brief Send a compassmot_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param throttle throttle (percent*10)
+ * @param current current (amps)
+ * @param interference interference (percent)
+ * @param CompensationX Motor Compensation X
+ * @param CompensationY Motor Compensation Y
+ * @param CompensationZ Motor Compensation Z
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_compassmot_status_send(mavlink_channel_t chan, uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
+ _mav_put_float(buf, 0, current);
+ _mav_put_float(buf, 4, CompensationX);
+ _mav_put_float(buf, 8, CompensationY);
+ _mav_put_float(buf, 12, CompensationZ);
+ _mav_put_uint16_t(buf, 16, throttle);
+ _mav_put_uint16_t(buf, 18, interference);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+#else
+ mavlink_compassmot_status_t packet;
+ packet.current = current;
+ packet.CompensationX = CompensationX;
+ packet.CompensationY = CompensationY;
+ packet.CompensationZ = CompensationZ;
+ packet.throttle = throttle;
+ packet.interference = interference;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_compassmot_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, current);
+ _mav_put_float(buf, 4, CompensationX);
+ _mav_put_float(buf, 8, CompensationY);
+ _mav_put_float(buf, 12, CompensationZ);
+ _mav_put_uint16_t(buf, 16, throttle);
+ _mav_put_uint16_t(buf, 18, interference);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+#else
+ mavlink_compassmot_status_t *packet = (mavlink_compassmot_status_t *)msgbuf;
+ packet->current = current;
+ packet->CompensationX = CompensationX;
+ packet->CompensationY = CompensationY;
+ packet->CompensationZ = CompensationZ;
+ packet->throttle = throttle;
+ packet->interference = interference;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE COMPASSMOT_STATUS UNPACKING
+
+
+/**
+ * @brief Get field throttle from compassmot_status message
+ *
+ * @return throttle (percent*10)
+ */
+static inline uint16_t mavlink_msg_compassmot_status_get_throttle(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 16);
+}
+
+/**
+ * @brief Get field current from compassmot_status message
+ *
+ * @return current (amps)
+ */
+static inline float mavlink_msg_compassmot_status_get_current(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field interference from compassmot_status message
+ *
+ * @return interference (percent)
+ */
+static inline uint16_t mavlink_msg_compassmot_status_get_interference(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 18);
+}
+
+/**
+ * @brief Get field CompensationX from compassmot_status message
+ *
+ * @return Motor Compensation X
+ */
+static inline float mavlink_msg_compassmot_status_get_CompensationX(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field CompensationY from compassmot_status message
+ *
+ * @return Motor Compensation Y
+ */
+static inline float mavlink_msg_compassmot_status_get_CompensationY(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field CompensationZ from compassmot_status message
+ *
+ * @return Motor Compensation Z
+ */
+static inline float mavlink_msg_compassmot_status_get_CompensationZ(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Decode a compassmot_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param compassmot_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_compassmot_status_decode(const mavlink_message_t* msg, mavlink_compassmot_status_t* compassmot_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ compassmot_status->current = mavlink_msg_compassmot_status_get_current(msg);
+ compassmot_status->CompensationX = mavlink_msg_compassmot_status_get_CompensationX(msg);
+ compassmot_status->CompensationY = mavlink_msg_compassmot_status_get_CompensationY(msg);
+ compassmot_status->CompensationZ = mavlink_msg_compassmot_status_get_CompensationZ(msg);
+ compassmot_status->throttle = mavlink_msg_compassmot_status_get_throttle(msg);
+ compassmot_status->interference = mavlink_msg_compassmot_status_get_interference(msg);
+#else
+ memcpy(compassmot_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+}
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h
index 9200eefa0d..7bad1b23de 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h
@@ -162,6 +162,40 @@ static inline void mavlink_msg_data16_send(mavlink_channel_t chan, uint8_t type,
#endif
}
+#if MAVLINK_MSG_ID_DATA16_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_data16_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_LEN);
+#endif
+#else
+ mavlink_data16_t *packet = (mavlink_data16_t *)msgbuf;
+ packet->type = type;
+ packet->len = len;
+ mav_array_memcpy(packet->data, data, sizeof(uint8_t)*16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)packet, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)packet, MAVLINK_MSG_ID_DATA16_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE DATA16 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h
index 3afedb7874..df7a2ec801 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h
@@ -162,6 +162,40 @@ static inline void mavlink_msg_data32_send(mavlink_channel_t chan, uint8_t type,
#endif
}
+#if MAVLINK_MSG_ID_DATA32_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_data32_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 32);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_LEN);
+#endif
+#else
+ mavlink_data32_t *packet = (mavlink_data32_t *)msgbuf;
+ packet->type = type;
+ packet->len = len;
+ mav_array_memcpy(packet->data, data, sizeof(uint8_t)*32);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)packet, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)packet, MAVLINK_MSG_ID_DATA32_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE DATA32 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h
index 6931ada167..c354f8908a 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h
@@ -162,6 +162,40 @@ static inline void mavlink_msg_data64_send(mavlink_channel_t chan, uint8_t type,
#endif
}
+#if MAVLINK_MSG_ID_DATA64_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_data64_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 64);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_LEN);
+#endif
+#else
+ mavlink_data64_t *packet = (mavlink_data64_t *)msgbuf;
+ packet->type = type;
+ packet->len = len;
+ mav_array_memcpy(packet->data, data, sizeof(uint8_t)*64);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)packet, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)packet, MAVLINK_MSG_ID_DATA64_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE DATA64 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h
index cffc7d7e7f..634e3f81d5 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h
@@ -162,6 +162,40 @@ static inline void mavlink_msg_data96_send(mavlink_channel_t chan, uint8_t type,
#endif
}
+#if MAVLINK_MSG_ID_DATA96_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_data96_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 96);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_LEN);
+#endif
+#else
+ mavlink_data96_t *packet = (mavlink_data96_t *)msgbuf;
+ packet->type = type;
+ packet->len = len;
+ mav_array_memcpy(packet->data, data, sizeof(uint8_t)*96);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)packet, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)packet, MAVLINK_MSG_ID_DATA96_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE DATA96 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h
index c6518c4199..d5f9e7132c 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h
@@ -256,6 +256,58 @@ static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_digicam_configure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint16_t(buf, 4, shutter_speed);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+ _mav_put_uint8_t(buf, 8, mode);
+ _mav_put_uint8_t(buf, 9, aperture);
+ _mav_put_uint8_t(buf, 10, iso);
+ _mav_put_uint8_t(buf, 11, exposure_type);
+ _mav_put_uint8_t(buf, 12, command_id);
+ _mav_put_uint8_t(buf, 13, engine_cut_off);
+ _mav_put_uint8_t(buf, 14, extra_param);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
+#endif
+#else
+ mavlink_digicam_configure_t *packet = (mavlink_digicam_configure_t *)msgbuf;
+ packet->extra_value = extra_value;
+ packet->shutter_speed = shutter_speed;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->mode = mode;
+ packet->aperture = aperture;
+ packet->iso = iso;
+ packet->exposure_type = exposure_type;
+ packet->command_id = command_id;
+ packet->engine_cut_off = engine_cut_off;
+ packet->extra_param = extra_param;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE DIGICAM_CONFIGURE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h
index bfa5414a39..68484f7b84 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h
@@ -245,6 +245,56 @@ static inline void mavlink_msg_digicam_control_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_digicam_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, session);
+ _mav_put_uint8_t(buf, 7, zoom_pos);
+ _mav_put_int8_t(buf, 8, zoom_step);
+ _mav_put_uint8_t(buf, 9, focus_lock);
+ _mav_put_uint8_t(buf, 10, shot);
+ _mav_put_uint8_t(buf, 11, command_id);
+ _mav_put_uint8_t(buf, 12, extra_param);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
+#endif
+#else
+ mavlink_digicam_control_t *packet = (mavlink_digicam_control_t *)msgbuf;
+ packet->extra_value = extra_value;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->session = session;
+ packet->zoom_pos = zoom_pos;
+ packet->zoom_step = zoom_step;
+ packet->focus_lock = focus_lock;
+ packet->shot = shot;
+ packet->command_id = command_id;
+ packet->extra_param = extra_param;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE DIGICAM_CONTROL UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h
index fe3677d53d..4021c7a096 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_fence_fetch_point_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_fence_fetch_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
+#endif
+#else
+ mavlink_fence_fetch_point_t *packet = (mavlink_fence_fetch_point_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->idx = idx;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FENCE_FETCH_POINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
index febda6cdc5..6fc2c83fc4 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t
#endif
}
+#if MAVLINK_MSG_ID_FENCE_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_fence_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, lat);
+ _mav_put_float(buf, 4, lng);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, idx);
+ _mav_put_uint8_t(buf, 11, count);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#endif
+#else
+ mavlink_fence_point_t *packet = (mavlink_fence_point_t *)msgbuf;
+ packet->lat = lat;
+ packet->lng = lng;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->idx = idx;
+ packet->count = count;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FENCE_POINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h
index 6120904061..c50d37724e 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t
#endif
}
+#if MAVLINK_MSG_ID_FENCE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_fence_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, breach_time);
+ _mav_put_uint16_t(buf, 4, breach_count);
+ _mav_put_uint8_t(buf, 6, breach_status);
+ _mav_put_uint8_t(buf, 7, breach_type);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
+#endif
+#else
+ mavlink_fence_status_t *packet = (mavlink_fence_status_t *)msgbuf;
+ packet->breach_time = breach_time;
+ packet->breach_count = breach_count;
+ packet->breach_status = breach_status;
+ packet->breach_type = breach_type;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FENCE_STATUS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h
index 2f5dea513a..acf031f62d 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_hwstatus_send(mavlink_channel_t chan, uint16_t Vc
#endif
}
+#if MAVLINK_MSG_ID_HWSTATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_hwstatus_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, Vcc);
+ _mav_put_uint8_t(buf, 2, I2Cerr);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_LEN);
+#endif
+#else
+ mavlink_hwstatus_t *packet = (mavlink_hwstatus_t *)msgbuf;
+ packet->Vcc = Vcc;
+ packet->I2Cerr = I2Cerr;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)packet, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)packet, MAVLINK_MSG_ID_HWSTATUS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE HWSTATUS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h
index 34743fd021..5fef937181 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h
@@ -234,6 +234,54 @@ static inline void mavlink_msg_limits_status_send(mavlink_channel_t chan, uint8_
#endif
}
+#if MAVLINK_MSG_ID_LIMITS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_limits_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, last_trigger);
+ _mav_put_uint32_t(buf, 4, last_action);
+ _mav_put_uint32_t(buf, 8, last_recovery);
+ _mav_put_uint32_t(buf, 12, last_clear);
+ _mav_put_uint16_t(buf, 16, breach_count);
+ _mav_put_uint8_t(buf, 18, limits_state);
+ _mav_put_uint8_t(buf, 19, mods_enabled);
+ _mav_put_uint8_t(buf, 20, mods_required);
+ _mav_put_uint8_t(buf, 21, mods_triggered);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
+#endif
+#else
+ mavlink_limits_status_t *packet = (mavlink_limits_status_t *)msgbuf;
+ packet->last_trigger = last_trigger;
+ packet->last_action = last_action;
+ packet->last_recovery = last_recovery;
+ packet->last_clear = last_clear;
+ packet->breach_count = breach_count;
+ packet->limits_state = limits_state;
+ packet->mods_enabled = mods_enabled;
+ packet->mods_required = mods_required;
+ packet->mods_triggered = mods_triggered;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LIMITS_STATUS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h
index 55f772bbc5..c64b2e9377 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_meminfo_send(mavlink_channel_t chan, uint16_t brk
#endif
}
+#if MAVLINK_MSG_ID_MEMINFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_meminfo_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t brkval, uint16_t freemem)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, brkval);
+ _mav_put_uint16_t(buf, 2, freemem);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_LEN);
+#endif
+#else
+ mavlink_meminfo_t *packet = (mavlink_meminfo_t *)msgbuf;
+ packet->brkval = brkval;
+ packet->freemem = freemem;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)packet, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)packet, MAVLINK_MSG_ID_MEMINFO_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MEMINFO UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h
index de717dfa4d..350bb0b785 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mount_configure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, mount_mode);
+ _mav_put_uint8_t(buf, 3, stab_roll);
+ _mav_put_uint8_t(buf, 4, stab_pitch);
+ _mav_put_uint8_t(buf, 5, stab_yaw);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
+#endif
+#else
+ mavlink_mount_configure_t *packet = (mavlink_mount_configure_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->mount_mode = mount_mode;
+ packet->stab_roll = stab_roll;
+ packet->stab_pitch = stab_pitch;
+ packet->stab_yaw = stab_yaw;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MOUNT_CONFIGURE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h
index 44416353ed..72d6e24197 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_mount_control_send(mavlink_channel_t chan, uint8_
#endif
}
+#if MAVLINK_MSG_ID_MOUNT_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mount_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, input_a);
+ _mav_put_int32_t(buf, 4, input_b);
+ _mav_put_int32_t(buf, 8, input_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, save_position);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
+#endif
+#else
+ mavlink_mount_control_t *packet = (mavlink_mount_control_t *)msgbuf;
+ packet->input_a = input_a;
+ packet->input_b = input_b;
+ packet->input_c = input_c;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->save_position = save_position;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MOUNT_CONTROL UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h
index 4905905dc5..c140dd2c7d 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_mount_status_send(mavlink_channel_t chan, uint8_t
#endif
}
+#if MAVLINK_MSG_ID_MOUNT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mount_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, pointing_a);
+ _mav_put_int32_t(buf, 4, pointing_b);
+ _mav_put_int32_t(buf, 8, pointing_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
+#endif
+#else
+ mavlink_mount_status_t *packet = (mavlink_mount_status_t *)msgbuf;
+ packet->pointing_a = pointing_a;
+ packet->pointing_b = pointing_b;
+ packet->pointing_c = pointing_c;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MOUNT_STATUS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h
index 8e9740e828..830eb4639a 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi,
#endif
}
+#if MAVLINK_MSG_ID_RADIO_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_radio_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, rxerrors);
+ _mav_put_uint16_t(buf, 2, fixed);
+ _mav_put_uint8_t(buf, 4, rssi);
+ _mav_put_uint8_t(buf, 5, remrssi);
+ _mav_put_uint8_t(buf, 6, txbuf);
+ _mav_put_uint8_t(buf, 7, noise);
+ _mav_put_uint8_t(buf, 8, remnoise);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_LEN);
+#endif
+#else
+ mavlink_radio_t *packet = (mavlink_radio_t *)msgbuf;
+ packet->rxerrors = rxerrors;
+ packet->fixed = fixed;
+ packet->rssi = rssi;
+ packet->remrssi = remrssi;
+ packet->txbuf = txbuf;
+ packet->noise = noise;
+ packet->remnoise = remnoise;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)packet, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)packet, MAVLINK_MSG_ID_RADIO_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RADIO UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h
index f057e3c335..4598251fe1 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_rally_fetch_point_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_rally_fetch_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
+#endif
+#else
+ mavlink_rally_fetch_point_t *packet = (mavlink_rally_fetch_point_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->idx = idx;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RALLY_FETCH_POINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h
index 2c21db4c0e..b44e764a94 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h
@@ -245,6 +245,56 @@ static inline void mavlink_msg_rally_point_send(mavlink_channel_t chan, uint8_t
#endif
}
+#if MAVLINK_MSG_ID_RALLY_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_rally_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lng);
+ _mav_put_int16_t(buf, 8, alt);
+ _mav_put_int16_t(buf, 10, break_alt);
+ _mav_put_uint16_t(buf, 12, land_dir);
+ _mav_put_uint8_t(buf, 14, target_system);
+ _mav_put_uint8_t(buf, 15, target_component);
+ _mav_put_uint8_t(buf, 16, idx);
+ _mav_put_uint8_t(buf, 17, count);
+ _mav_put_uint8_t(buf, 18, flags);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_LEN);
+#endif
+#else
+ mavlink_rally_point_t *packet = (mavlink_rally_point_t *)msgbuf;
+ packet->lat = lat;
+ packet->lng = lng;
+ packet->alt = alt;
+ packet->break_alt = break_alt;
+ packet->land_dir = land_dir;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->idx = idx;
+ packet->count = count;
+ packet->flags = flags;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_POINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RALLY_POINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h
index c476447a87..464ce8a47f 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_rangefinder_send(mavlink_channel_t chan, float di
#endif
}
+#if MAVLINK_MSG_ID_RANGEFINDER_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_rangefinder_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float distance, float voltage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, distance);
+ _mav_put_float(buf, 4, voltage);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_LEN);
+#endif
+#else
+ mavlink_rangefinder_t *packet = (mavlink_rangefinder_t *)msgbuf;
+ packet->distance = distance;
+ packet->voltage = voltage;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)packet, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)packet, MAVLINK_MSG_ID_RANGEFINDER_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RANGEFINDER UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h
index 31b7d989de..d18f31c954 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h
@@ -267,6 +267,60 @@ static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16
#endif
}
+#if MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_sensor_offsets_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, mag_declination);
+ _mav_put_int32_t(buf, 4, raw_press);
+ _mav_put_int32_t(buf, 8, raw_temp);
+ _mav_put_float(buf, 12, gyro_cal_x);
+ _mav_put_float(buf, 16, gyro_cal_y);
+ _mav_put_float(buf, 20, gyro_cal_z);
+ _mav_put_float(buf, 24, accel_cal_x);
+ _mav_put_float(buf, 28, accel_cal_y);
+ _mav_put_float(buf, 32, accel_cal_z);
+ _mav_put_int16_t(buf, 36, mag_ofs_x);
+ _mav_put_int16_t(buf, 38, mag_ofs_y);
+ _mav_put_int16_t(buf, 40, mag_ofs_z);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
+#endif
+#else
+ mavlink_sensor_offsets_t *packet = (mavlink_sensor_offsets_t *)msgbuf;
+ packet->mag_declination = mag_declination;
+ packet->raw_press = raw_press;
+ packet->raw_temp = raw_temp;
+ packet->gyro_cal_x = gyro_cal_x;
+ packet->gyro_cal_y = gyro_cal_y;
+ packet->gyro_cal_z = gyro_cal_z;
+ packet->accel_cal_x = accel_cal_x;
+ packet->accel_cal_y = accel_cal_y;
+ packet->accel_cal_z = accel_cal_z;
+ packet->mag_ofs_x = mag_ofs_x;
+ packet->mag_ofs_y = mag_ofs_y;
+ packet->mag_ofs_z = mag_ofs_z;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SENSOR_OFFSETS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h
index b2c629c39a..fc6aa71e06 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_mag_offsets_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int16_t(buf, 0, mag_ofs_x);
+ _mav_put_int16_t(buf, 2, mag_ofs_y);
+ _mav_put_int16_t(buf, 4, mag_ofs_z);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
+#endif
+#else
+ mavlink_set_mag_offsets_t *packet = (mavlink_set_mag_offsets_t *)msgbuf;
+ packet->mag_ofs_x = mag_ofs_x;
+ packet->mag_ofs_y = mag_ofs_y;
+ packet->mag_ofs_z = mag_ofs_z;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_MAG_OFFSETS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h
index 8ef44f76d5..48cfb6ffd5 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h
@@ -256,6 +256,58 @@ static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll,
#endif
}
+#if MAVLINK_MSG_ID_SIMSTATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_simstate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, xacc);
+ _mav_put_float(buf, 16, yacc);
+ _mav_put_float(buf, 20, zacc);
+ _mav_put_float(buf, 24, xgyro);
+ _mav_put_float(buf, 28, ygyro);
+ _mav_put_float(buf, 32, zgyro);
+ _mav_put_int32_t(buf, 36, lat);
+ _mav_put_int32_t(buf, 40, lng);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_LEN);
+#endif
+#else
+ mavlink_simstate_t *packet = (mavlink_simstate_t *)msgbuf;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->xacc = xacc;
+ packet->yacc = yacc;
+ packet->zacc = zacc;
+ packet->xgyro = xgyro;
+ packet->ygyro = ygyro;
+ packet->zgyro = zgyro;
+ packet->lat = lat;
+ packet->lng = lng;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)packet, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)packet, MAVLINK_MSG_ID_SIMSTATE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SIMSTATE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h
index 7608a7bd10..5d5edc4cc3 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_wind_send(mavlink_channel_t chan, float direction
#endif
}
+#if MAVLINK_MSG_ID_WIND_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_wind_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float direction, float speed, float speed_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, direction);
+ _mav_put_float(buf, 4, speed);
+ _mav_put_float(buf, 8, speed_z);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_LEN);
+#endif
+#else
+ mavlink_wind_t *packet = (mavlink_wind_t *)msgbuf;
+ packet->direction = direction;
+ packet->speed = speed;
+ packet->speed_z = speed_z;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)packet, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)packet, MAVLINK_MSG_ID_WIND_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE WIND UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h
index b2496334f7..489553ea4d 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h
@@ -1398,6 +1398,59 @@ static void mavlink_test_rally_fetch_point(uint8_t system_id, uint8_t component_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
+static void mavlink_test_compassmot_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_compassmot_status_t packet_in = {
+ 17.0,
+ }45.0,
+ }73.0,
+ }101.0,
+ }18067,
+ }18171,
+ };
+ mavlink_compassmot_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.current = packet_in.current;
+ packet1.CompensationX = packet_in.CompensationX;
+ packet1.CompensationY = packet_in.CompensationY;
+ packet1.CompensationZ = packet_in.CompensationZ;
+ packet1.throttle = packet_in.throttle;
+ packet1.interference = packet_in.interference;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_compassmot_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_compassmot_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_compassmot_status_pack(system_id, component_id, &msg , packet1.throttle , packet1.current , packet1.interference , packet1.CompensationX , packet1.CompensationY , packet1.CompensationZ );
+ mavlink_msg_compassmot_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_compassmot_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.throttle , packet1.current , packet1.interference , packet1.CompensationX , packet1.CompensationY , packet1.CompensationZ );
+ mavlink_msg_compassmot_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
+ MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */
+ MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */
+ MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
+ MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */
+ MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
+ MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
diff --git a/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h b/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h
index ed7c86bcb8..e78d5687aa 100644
--- a/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h
+++ b/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h
@@ -366,6 +366,78 @@ static inline void mavlink_msg_aq_telemetry_f_send(mavlink_channel_t chan, uint1
#endif
}
+#if MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_aq_telemetry_f_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Index, float value1, float value2, float value3, float value4, float value5, float value6, float value7, float value8, float value9, float value10, float value11, float value12, float value13, float value14, float value15, float value16, float value17, float value18, float value19, float value20)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, value1);
+ _mav_put_float(buf, 4, value2);
+ _mav_put_float(buf, 8, value3);
+ _mav_put_float(buf, 12, value4);
+ _mav_put_float(buf, 16, value5);
+ _mav_put_float(buf, 20, value6);
+ _mav_put_float(buf, 24, value7);
+ _mav_put_float(buf, 28, value8);
+ _mav_put_float(buf, 32, value9);
+ _mav_put_float(buf, 36, value10);
+ _mav_put_float(buf, 40, value11);
+ _mav_put_float(buf, 44, value12);
+ _mav_put_float(buf, 48, value13);
+ _mav_put_float(buf, 52, value14);
+ _mav_put_float(buf, 56, value15);
+ _mav_put_float(buf, 60, value16);
+ _mav_put_float(buf, 64, value17);
+ _mav_put_float(buf, 68, value18);
+ _mav_put_float(buf, 72, value19);
+ _mav_put_float(buf, 76, value20);
+ _mav_put_uint16_t(buf, 80, Index);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#endif
+#else
+ mavlink_aq_telemetry_f_t *packet = (mavlink_aq_telemetry_f_t *)msgbuf;
+ packet->value1 = value1;
+ packet->value2 = value2;
+ packet->value3 = value3;
+ packet->value4 = value4;
+ packet->value5 = value5;
+ packet->value6 = value6;
+ packet->value7 = value7;
+ packet->value8 = value8;
+ packet->value9 = value9;
+ packet->value10 = value10;
+ packet->value11 = value11;
+ packet->value12 = value12;
+ packet->value13 = value13;
+ packet->value14 = value14;
+ packet->value15 = value15;
+ packet->value16 = value16;
+ packet->value17 = value17;
+ packet->value18 = value18;
+ packet->value19 = value19;
+ packet->value20 = value20;
+ packet->Index = Index;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE AQ_TELEMETRY_F UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/autoquad/version.h b/mavlink/include/mavlink/v1.0/autoquad/version.h
index d125e92b1a..5d2f33b601 100644
--- a/mavlink/include/mavlink/v1.0/autoquad/version.h
+++ b/mavlink/include/mavlink/v1.0/autoquad/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Tue Feb 4 15:27:43 2014"
+#define MAVLINK_BUILD_DATE "Sun Apr 13 09:38:19 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
diff --git a/mavlink/include/mavlink/v1.0/common/common.h b/mavlink/include/mavlink/v1.0/common/common.h
index 7e1cf765bf..020211d406 100644
--- a/mavlink/include/mavlink/v1.0/common/common.h
+++ b/mavlink/include/mavlink/v1.0/common/common.h
@@ -12,15 +12,15 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 0, 0, 0, 0, 0, 13, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
+#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 0, 0, 0, 0, 0, 29, 223, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
#include "../protocol.h"
@@ -79,7 +79,8 @@ enum MAV_TYPE
MAV_TYPE_TRICOPTER=15, /* Octorotor | */
MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */
MAV_TYPE_KITE=17, /* Flapping wing | */
- MAV_TYPE_ENUM_END=18, /* | */
+ MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */
+ MAV_TYPE_ENUM_END=19, /* | */
};
#endif
@@ -228,7 +229,8 @@ enum MAV_SYS_STATUS_SENSOR
MAV_SYS_STATUS_SENSOR_3D_GYRO2=131072, /* 0x20000 2nd 3D gyro | */
MAV_SYS_STATUS_SENSOR_3D_ACCEL2=262144, /* 0x40000 2nd 3D accelerometer | */
MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */
- MAV_SYS_STATUS_SENSOR_ENUM_END=524289, /* | */
+ MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */
+ MAV_SYS_STATUS_SENSOR_ENUM_END=1048577, /* | */
};
#endif
@@ -242,7 +244,9 @@ enum MAV_FRAME
MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */
MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */
MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */
- MAV_FRAME_ENUM_END=5, /* | */
+ MAV_FRAME_GLOBAL_INT=5, /* Global coordinate frame with some fields as scaled integers, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations. | */
+ MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* Global coordinate frame with some fields as scaled integers, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations. | */
+ MAV_FRAME_ENUM_END=7, /* | */
};
#endif
@@ -261,6 +265,57 @@ enum MAVLINK_DATA_STREAM_TYPE
};
#endif
+/** @brief */
+#ifndef HAVE_ENUM_FENCE_ACTION
+#define HAVE_ENUM_FENCE_ACTION
+enum FENCE_ACTION
+{
+ FENCE_ACTION_NONE=0, /* Disable fenced mode | */
+ FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */
+ FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */
+ FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */
+ FENCE_ACTION_ENUM_END=4, /* | */
+};
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_FENCE_BREACH
+#define HAVE_ENUM_FENCE_BREACH
+enum FENCE_BREACH
+{
+ FENCE_BREACH_NONE=0, /* No last fence breach | */
+ FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */
+ FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */
+ FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */
+ FENCE_BREACH_ENUM_END=4, /* | */
+};
+#endif
+
+/** @brief Enumeration of possible mount operation modes */
+#ifndef HAVE_ENUM_MAV_MOUNT_MODE
+#define HAVE_ENUM_MAV_MOUNT_MODE
+enum MAV_MOUNT_MODE
+{
+ MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */
+ MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */
+ MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
+ MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
+ MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
+ MAV_MOUNT_MODE_ENUM_END=5, /* | */
+};
+#endif
+
+/** @brief Enumeration of distance sensor types */
+#ifndef HAVE_ENUM_MAV_DISTANCE_SENSOR
+#define HAVE_ENUM_MAV_DISTANCE_SENSOR
+enum MAV_DISTANCE_SENSOR
+{
+ MAV_DISTANCE_SENSOR_LASER=0, /* Laser altimeter, e.g. LightWare SF02/F or PulsedLight units | */
+ MAV_DISTANCE_SENSOR_ULTRASOUND=1, /* Laser altimeter, e.g. MaxBotix units | */
+ MAV_DISTANCE_SENSOR_ENUM_END=2, /* | */
+};
+#endif
+
/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */
#ifndef HAVE_ENUM_MAV_CMD
#define HAVE_ENUM_MAV_CMD
@@ -275,6 +330,7 @@ enum MAV_CMD
MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
+ MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
@@ -292,8 +348,16 @@ enum MAV_CMD
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
+ MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */
+ MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */
+ MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
+ MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */
+ MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
+ MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
@@ -433,6 +497,48 @@ enum MAV_SEVERITY
};
#endif
+/** @brief Power supply status flags (bitmask) */
+#ifndef HAVE_ENUM_MAV_POWER_STATUS
+#define HAVE_ENUM_MAV_POWER_STATUS
+enum MAV_POWER_STATUS
+{
+ MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */
+ MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */
+ MAV_POWER_STATUS_USB_CONNECTED=4, /* USB power is connected | */
+ MAV_POWER_STATUS_PERIPH_OVERCURRENT=8, /* peripheral supply is in over-current state | */
+ MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */
+ MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */
+ MAV_POWER_STATUS_ENUM_END=33, /* | */
+};
+#endif
+
+/** @brief SERIAL_CONTROL device types */
+#ifndef HAVE_ENUM_SERIAL_CONTROL_DEV
+#define HAVE_ENUM_SERIAL_CONTROL_DEV
+enum SERIAL_CONTROL_DEV
+{
+ SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */
+ SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */
+ SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */
+ SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */
+ SERIAL_CONTROL_DEV_ENUM_END=4, /* | */
+};
+#endif
+
+/** @brief SERIAL_CONTROL flags (bitmask) */
+#ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG
+#define HAVE_ENUM_SERIAL_CONTROL_FLAG
+enum SERIAL_CONTROL_FLAG
+{
+ SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */
+ SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */
+ SERIAL_CONTROL_FLAG_EXCLUSIVE=4, /* Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set | */
+ SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */
+ SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */
+ SERIAL_CONTROL_FLAG_ENUM_END=17, /* | */
+};
+#endif
+
// MAVLINK VERSION
@@ -500,6 +606,7 @@ enum MAV_SEVERITY
#include "./mavlink_msg_nav_controller_output.h"
#include "./mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h"
#include "./mavlink_msg_state_correction.h"
+#include "./mavlink_msg_rc_channels.h"
#include "./mavlink_msg_request_data_stream.h"
#include "./mavlink_msg_data_stream.h"
#include "./mavlink_msg_manual_control.h"
@@ -538,8 +645,11 @@ enum MAV_SEVERITY
#include "./mavlink_msg_log_request_end.h"
#include "./mavlink_msg_gps_inject_data.h"
#include "./mavlink_msg_gps2_raw.h"
+#include "./mavlink_msg_power_status.h"
+#include "./mavlink_msg_serial_control.h"
#include "./mavlink_msg_data_transmission_handshake.h"
#include "./mavlink_msg_encapsulated_data.h"
+#include "./mavlink_msg_distance_sensor.h"
#include "./mavlink_msg_battery_status.h"
#include "./mavlink_msg_setpoint_8dof.h"
#include "./mavlink_msg_setpoint_6dof.h"
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h
index 8ddf5bf099..ff2f104d40 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t ti
#endif
}
+#if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, roll);
+ _mav_put_float(buf, 8, pitch);
+ _mav_put_float(buf, 12, yaw);
+ _mav_put_float(buf, 16, rollspeed);
+ _mav_put_float(buf, 20, pitchspeed);
+ _mav_put_float(buf, 24, yawspeed);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
+#endif
+#else
+ mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->rollspeed = rollspeed;
+ packet->pitchspeed = pitchspeed;
+ packet->yawspeed = yawspeed;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE ATTITUDE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h
index 9f8d587598..3b97b40d0d 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h
@@ -223,6 +223,52 @@ static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, q1);
+ _mav_put_float(buf, 8, q2);
+ _mav_put_float(buf, 12, q3);
+ _mav_put_float(buf, 16, q4);
+ _mav_put_float(buf, 20, rollspeed);
+ _mav_put_float(buf, 24, pitchspeed);
+ _mav_put_float(buf, 28, yawspeed);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
+#endif
+#else
+ mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->q1 = q1;
+ packet->q2 = q2;
+ packet->q3 = q3;
+ packet->q4 = q4;
+ packet->rollspeed = rollspeed;
+ packet->pitchspeed = pitchspeed;
+ packet->yawspeed = yawspeed;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE ATTITUDE_QUATERNION UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h
index 5703a59871..f31b6bbf48 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h
@@ -146,6 +146,38 @@ static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char
#endif
}
+#if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_char_array(buf, 0, key, 32);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
+#endif
+#else
+ mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf;
+
+ mav_array_memcpy(packet->key, key, sizeof(char)*32);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE AUTH_KEY UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h
index 03e4d569e6..faaabf9f70 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h
@@ -256,6 +256,58 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8
#endif
}
+#if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, current_consumed);
+ _mav_put_int32_t(buf, 4, energy_consumed);
+ _mav_put_uint16_t(buf, 8, voltage_cell_1);
+ _mav_put_uint16_t(buf, 10, voltage_cell_2);
+ _mav_put_uint16_t(buf, 12, voltage_cell_3);
+ _mav_put_uint16_t(buf, 14, voltage_cell_4);
+ _mav_put_uint16_t(buf, 16, voltage_cell_5);
+ _mav_put_uint16_t(buf, 18, voltage_cell_6);
+ _mav_put_int16_t(buf, 20, current_battery);
+ _mav_put_uint8_t(buf, 22, accu_id);
+ _mav_put_int8_t(buf, 23, battery_remaining);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
+#endif
+#else
+ mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf;
+ packet->current_consumed = current_consumed;
+ packet->energy_consumed = energy_consumed;
+ packet->voltage_cell_1 = voltage_cell_1;
+ packet->voltage_cell_2 = voltage_cell_2;
+ packet->voltage_cell_3 = voltage_cell_3;
+ packet->voltage_cell_4 = voltage_cell_4;
+ packet->voltage_cell_5 = voltage_cell_5;
+ packet->voltage_cell_6 = voltage_cell_6;
+ packet->current_battery = current_battery;
+ packet->accu_id = accu_id;
+ packet->battery_remaining = battery_remaining;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE BATTERY_STATUS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h
index 0b6de930d2..3f0987f10a 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h
@@ -173,6 +173,42 @@ static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t ch
#endif
}
+#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_change_operator_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, control_request);
+ _mav_put_uint8_t(buf, 2, version);
+ _mav_put_char_array(buf, 3, passkey, 25);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
+#endif
+#else
+ mavlink_change_operator_control_t *packet = (mavlink_change_operator_control_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->control_request = control_request;
+ packet->version = version;
+ mav_array_memcpy(packet->passkey, passkey, sizeof(char)*25);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h
index c6f6a28e4b..768e7ed5ca 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_
#endif
}
+#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_change_operator_control_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, gcs_system_id);
+ _mav_put_uint8_t(buf, 1, control_request);
+ _mav_put_uint8_t(buf, 2, ack);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
+#endif
+#else
+ mavlink_change_operator_control_ack_t *packet = (mavlink_change_operator_control_ack_t *)msgbuf;
+ packet->gcs_system_id = gcs_system_id;
+ packet->control_request = control_request;
+ packet->ack = ack;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h
index dca2fe6819..d3d1630419 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t
#endif
}
+#if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, command);
+ _mav_put_uint8_t(buf, 2, result);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
+#endif
+#else
+ mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf;
+ packet->command = command;
+ packet->result = result;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE COMMAND_ACK UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h
index 8f705c0dd2..161896b973 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h
@@ -256,6 +256,58 @@ static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t
#endif
}
+#if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, param1);
+ _mav_put_float(buf, 4, param2);
+ _mav_put_float(buf, 8, param3);
+ _mav_put_float(buf, 12, param4);
+ _mav_put_float(buf, 16, param5);
+ _mav_put_float(buf, 20, param6);
+ _mav_put_float(buf, 24, param7);
+ _mav_put_uint16_t(buf, 28, command);
+ _mav_put_uint8_t(buf, 30, target_system);
+ _mav_put_uint8_t(buf, 31, target_component);
+ _mav_put_uint8_t(buf, 32, confirmation);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
+#endif
+#else
+ mavlink_command_long_t *packet = (mavlink_command_long_t *)msgbuf;
+ packet->param1 = param1;
+ packet->param2 = param2;
+ packet->param3 = param3;
+ packet->param4 = param4;
+ packet->param5 = param5;
+ packet->param6 = param6;
+ packet->param7 = param7;
+ packet->command = command;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->confirmation = confirmation;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE COMMAND_LONG UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h
index dc0768e128..640ffebf44 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t
#endif
}
+#if MAVLINK_MSG_ID_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, message_rate);
+ _mav_put_uint8_t(buf, 2, stream_id);
+ _mav_put_uint8_t(buf, 3, on_off);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN);
+#endif
+#else
+ mavlink_data_stream_t *packet = (mavlink_data_stream_t *)msgbuf;
+ packet->message_rate = message_rate;
+ packet->stream_id = stream_id;
+ packet->on_off = on_off;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE DATA_STREAM UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h
index fdd8fddd87..d84a73709d 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_
#endif
}
+#if MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, size);
+ _mav_put_uint16_t(buf, 4, width);
+ _mav_put_uint16_t(buf, 6, height);
+ _mav_put_uint16_t(buf, 8, packets);
+ _mav_put_uint8_t(buf, 10, type);
+ _mav_put_uint8_t(buf, 11, payload);
+ _mav_put_uint8_t(buf, 12, jpg_quality);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
+#endif
+#else
+ mavlink_data_transmission_handshake_t *packet = (mavlink_data_transmission_handshake_t *)msgbuf;
+ packet->size = size;
+ packet->width = width;
+ packet->height = height;
+ packet->packets = packets;
+ packet->type = type;
+ packet->payload = payload;
+ packet->jpg_quality = jpg_quality;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h
index 9a6ed87eeb..2102af8623 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_
#endif
}
+#if MAVLINK_MSG_ID_DEBUG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, value);
+ _mav_put_uint8_t(buf, 8, ind);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN);
+#endif
+#else
+ mavlink_debug_t *packet = (mavlink_debug_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->value = value;
+ packet->ind = ind;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE DEBUG UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h
index 6cfc75212e..67c339e898 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h
@@ -184,6 +184,44 @@ static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const cha
#endif
}
+#if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, x);
+ _mav_put_float(buf, 12, y);
+ _mav_put_float(buf, 16, z);
+ _mav_put_char_array(buf, 20, name, 10);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
+#endif
+#else
+ mavlink_debug_vect_t *packet = (mavlink_debug_vect_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ mav_array_memcpy(packet->name, name, sizeof(char)*10);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE DEBUG_VECT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h
new file mode 100644
index 0000000000..39b3843966
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h
@@ -0,0 +1,377 @@
+// MESSAGE DISTANCE_SENSOR PACKING
+
+#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132
+
+typedef struct __mavlink_distance_sensor_t
+{
+ uint32_t time_boot_ms; ///< Time since system boot
+ uint16_t min_distance; ///< Minimum distance the sensor can measure in centimeters
+ uint16_t max_distance; ///< Maximum distance the sensor can measure in centimeters
+ uint16_t current_distance; ///< Current distance reading
+ uint8_t type; ///< Type from MAV_DISTANCE_SENSOR enum.
+ uint8_t id; ///< Onboard ID of the sensor
+ uint8_t orientation; ///< Direction the sensor faces from FIXME enum.
+ uint8_t covariance; ///< Measurement covariance in centimeters, 0 for unknown / invalid readings
+} mavlink_distance_sensor_t;
+
+#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14
+#define MAVLINK_MSG_ID_132_LEN 14
+
+#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85
+#define MAVLINK_MSG_ID_132_CRC 85
+
+
+
+#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \
+ "DISTANCE_SENSOR", \
+ 8, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \
+ { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \
+ { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \
+ { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \
+ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \
+ { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \
+ { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \
+ { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a distance_sensor message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Time since system boot
+ * @param type Type from MAV_DISTANCE_SENSOR enum.
+ * @param id Onboard ID of the sensor
+ * @param orientation Direction the sensor faces from FIXME enum.
+ * @param min_distance Minimum distance the sensor can measure in centimeters
+ * @param max_distance Maximum distance the sensor can measure in centimeters
+ * @param current_distance Current distance reading
+ * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t type, uint8_t id, uint8_t orientation, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, min_distance);
+ _mav_put_uint16_t(buf, 6, max_distance);
+ _mav_put_uint16_t(buf, 8, current_distance);
+ _mav_put_uint8_t(buf, 10, type);
+ _mav_put_uint8_t(buf, 11, id);
+ _mav_put_uint8_t(buf, 12, orientation);
+ _mav_put_uint8_t(buf, 13, covariance);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#else
+ mavlink_distance_sensor_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.min_distance = min_distance;
+ packet.max_distance = max_distance;
+ packet.current_distance = current_distance;
+ packet.type = type;
+ packet.id = id;
+ packet.orientation = orientation;
+ packet.covariance = covariance;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a distance_sensor message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Time since system boot
+ * @param type Type from MAV_DISTANCE_SENSOR enum.
+ * @param id Onboard ID of the sensor
+ * @param orientation Direction the sensor faces from FIXME enum.
+ * @param min_distance Minimum distance the sensor can measure in centimeters
+ * @param max_distance Maximum distance the sensor can measure in centimeters
+ * @param current_distance Current distance reading
+ * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t type,uint8_t id,uint8_t orientation,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, min_distance);
+ _mav_put_uint16_t(buf, 6, max_distance);
+ _mav_put_uint16_t(buf, 8, current_distance);
+ _mav_put_uint8_t(buf, 10, type);
+ _mav_put_uint8_t(buf, 11, id);
+ _mav_put_uint8_t(buf, 12, orientation);
+ _mav_put_uint8_t(buf, 13, covariance);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#else
+ mavlink_distance_sensor_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.min_distance = min_distance;
+ packet.max_distance = max_distance;
+ packet.current_distance = current_distance;
+ packet.type = type;
+ packet.id = id;
+ packet.orientation = orientation;
+ packet.covariance = covariance;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a distance_sensor struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param distance_sensor C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor)
+{
+ return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->covariance);
+}
+
+/**
+ * @brief Encode a distance_sensor struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param distance_sensor C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor)
+{
+ return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->covariance);
+}
+
+/**
+ * @brief Send a distance_sensor message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Time since system boot
+ * @param type Type from MAV_DISTANCE_SENSOR enum.
+ * @param id Onboard ID of the sensor
+ * @param orientation Direction the sensor faces from FIXME enum.
+ * @param min_distance Minimum distance the sensor can measure in centimeters
+ * @param max_distance Maximum distance the sensor can measure in centimeters
+ * @param current_distance Current distance reading
+ * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type, uint8_t id, uint8_t orientation, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, min_distance);
+ _mav_put_uint16_t(buf, 6, max_distance);
+ _mav_put_uint16_t(buf, 8, current_distance);
+ _mav_put_uint8_t(buf, 10, type);
+ _mav_put_uint8_t(buf, 11, id);
+ _mav_put_uint8_t(buf, 12, orientation);
+ _mav_put_uint8_t(buf, 13, covariance);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#endif
+#else
+ mavlink_distance_sensor_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.min_distance = min_distance;
+ packet.max_distance = max_distance;
+ packet.current_distance = current_distance;
+ packet.type = type;
+ packet.id = id;
+ packet.orientation = orientation;
+ packet.covariance = covariance;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type, uint8_t id, uint8_t orientation, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, min_distance);
+ _mav_put_uint16_t(buf, 6, max_distance);
+ _mav_put_uint16_t(buf, 8, current_distance);
+ _mav_put_uint8_t(buf, 10, type);
+ _mav_put_uint8_t(buf, 11, id);
+ _mav_put_uint8_t(buf, 12, orientation);
+ _mav_put_uint8_t(buf, 13, covariance);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#endif
+#else
+ mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->min_distance = min_distance;
+ packet->max_distance = max_distance;
+ packet->current_distance = current_distance;
+ packet->type = type;
+ packet->id = id;
+ packet->orientation = orientation;
+ packet->covariance = covariance;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DISTANCE_SENSOR UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from distance_sensor message
+ *
+ * @return Time since system boot
+ */
+static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field type from distance_sensor message
+ *
+ * @return Type from MAV_DISTANCE_SENSOR enum.
+ */
+static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 10);
+}
+
+/**
+ * @brief Get field id from distance_sensor message
+ *
+ * @return Onboard ID of the sensor
+ */
+static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 11);
+}
+
+/**
+ * @brief Get field orientation from distance_sensor message
+ *
+ * @return Direction the sensor faces from FIXME enum.
+ */
+static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 12);
+}
+
+/**
+ * @brief Get field min_distance from distance_sensor message
+ *
+ * @return Minimum distance the sensor can measure in centimeters
+ */
+static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field max_distance from distance_sensor message
+ *
+ * @return Maximum distance the sensor can measure in centimeters
+ */
+static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 6);
+}
+
+/**
+ * @brief Get field current_distance from distance_sensor message
+ *
+ * @return Current distance reading
+ */
+static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 8);
+}
+
+/**
+ * @brief Get field covariance from distance_sensor message
+ *
+ * @return Measurement covariance in centimeters, 0 for unknown / invalid readings
+ */
+static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 13);
+}
+
+/**
+ * @brief Decode a distance_sensor message into a struct
+ *
+ * @param msg The message to decode
+ * @param distance_sensor C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg);
+ distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg);
+ distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg);
+ distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg);
+ distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg);
+ distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg);
+ distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg);
+ distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg);
+#else
+ memcpy(distance_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
+#endif
+}
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h
index 5900ea8388..dacd7c9f40 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h
@@ -151,6 +151,38 @@ static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_encapsulated_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, seqnr);
+ _mav_put_uint8_t_array(buf, 2, data, 253);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
+#endif
+#else
+ mavlink_encapsulated_data_t *packet = (mavlink_encapsulated_data_t *)msgbuf;
+ packet->seqnr = seqnr;
+ mav_array_memcpy(packet->data, data, sizeof(uint8_t)*253);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE ENCAPSULATED_DATA UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h
index 4f31698d50..81c7031ced 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h
@@ -162,6 +162,40 @@ static inline void mavlink_msg_file_transfer_dir_list_send(mavlink_channel_t cha
#endif
}
+#if MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_file_transfer_dir_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t transfer_uid, const char *dir_path, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint8_t(buf, 248, flags);
+ _mav_put_char_array(buf, 8, dir_path, 240);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN);
+#endif
+#else
+ mavlink_file_transfer_dir_list_t *packet = (mavlink_file_transfer_dir_list_t *)msgbuf;
+ packet->transfer_uid = transfer_uid;
+ packet->flags = flags;
+ mav_array_memcpy(packet->dir_path, dir_path, sizeof(char)*240);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FILE_TRANSFER_DIR_LIST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h
index fc6247faca..04981fa85a 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_file_transfer_res_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_file_transfer_res_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t transfer_uid, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint8_t(buf, 8, result);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN);
+#endif
+#else
+ mavlink_file_transfer_res_t *packet = (mavlink_file_transfer_res_t *)msgbuf;
+ packet->transfer_uid = transfer_uid;
+ packet->result = result;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FILE_TRANSFER_RES UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h
index 05be77339b..7b1fba519a 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h
@@ -184,6 +184,44 @@ static inline void mavlink_msg_file_transfer_start_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_file_transfer_start_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, transfer_uid);
+ _mav_put_uint32_t(buf, 8, file_size);
+ _mav_put_uint8_t(buf, 252, direction);
+ _mav_put_uint8_t(buf, 253, flags);
+ _mav_put_char_array(buf, 12, dest_path, 240);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN);
+#endif
+#else
+ mavlink_file_transfer_start_t *packet = (mavlink_file_transfer_start_t *)msgbuf;
+ packet->transfer_uid = transfer_uid;
+ packet->file_size = file_size;
+ packet->direction = direction;
+ packet->flags = flags;
+ mav_array_memcpy(packet->dest_path, dest_path, sizeof(char)*240);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FILE_TRANSFER_START UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h
index 7ed3d2a636..ba15bf3654 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h
@@ -234,6 +234,54 @@ static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat);
+ _mav_put_int32_t(buf, 8, lon);
+ _mav_put_int32_t(buf, 12, alt);
+ _mav_put_int32_t(buf, 16, relative_alt);
+ _mav_put_int16_t(buf, 20, vx);
+ _mav_put_int16_t(buf, 22, vy);
+ _mav_put_int16_t(buf, 24, vz);
+ _mav_put_uint16_t(buf, 26, hdg);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
+#endif
+#else
+ mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt = alt;
+ packet->relative_alt = relative_alt;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->hdg = hdg;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE GLOBAL_POSITION_INT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h
index 1a1c97199e..77d735cf4f 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel
#endif
}
+#if MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_global_position_setpoint_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, latitude);
+ _mav_put_int32_t(buf, 4, longitude);
+ _mav_put_int32_t(buf, 8, altitude);
+ _mav_put_int16_t(buf, 12, yaw);
+ _mav_put_uint8_t(buf, 14, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN);
+#endif
+#else
+ mavlink_global_position_setpoint_int_t *packet = (mavlink_global_position_setpoint_int_t *)msgbuf;
+ packet->latitude = latitude;
+ packet->longitude = longitude;
+ packet->altitude = altitude;
+ packet->yaw = yaw;
+ packet->coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE GLOBAL_POSITION_SETPOINT_INT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h
index f7be74c917..b2b75d7ef5 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_chan
#endif
}
+#if MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, usec);
+ _mav_put_float(buf, 8, x);
+ _mav_put_float(buf, 12, y);
+ _mav_put_float(buf, 16, z);
+ _mav_put_float(buf, 20, roll);
+ _mav_put_float(buf, 24, pitch);
+ _mav_put_float(buf, 28, yaw);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
+#endif
+#else
+ mavlink_global_vision_position_estimate_t *packet = (mavlink_global_vision_position_estimate_t *)msgbuf;
+ packet->usec = usec;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h
index 17e5bd0026..b184e7c9cc 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h
@@ -267,6 +267,60 @@ static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t ti
#endif
}
+#if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lon);
+ _mav_put_int32_t(buf, 16, alt);
+ _mav_put_uint32_t(buf, 20, dgps_age);
+ _mav_put_uint16_t(buf, 24, eph);
+ _mav_put_uint16_t(buf, 26, epv);
+ _mav_put_uint16_t(buf, 28, vel);
+ _mav_put_uint16_t(buf, 30, cog);
+ _mav_put_uint8_t(buf, 32, fix_type);
+ _mav_put_uint8_t(buf, 33, satellites_visible);
+ _mav_put_uint8_t(buf, 34, dgps_numch);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
+#endif
+#else
+ mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt = alt;
+ packet->dgps_age = dgps_age;
+ packet->eph = eph;
+ packet->epv = epv;
+ packet->vel = vel;
+ packet->cog = cog;
+ packet->fix_type = fix_type;
+ packet->satellites_visible = satellites_visible;
+ packet->dgps_numch = dgps_numch;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE GPS2_RAW UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h
index 016e9cb0e6..1589c8ca59 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, in
#endif
}
+#if MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, latitude);
+ _mav_put_int32_t(buf, 4, longitude);
+ _mav_put_int32_t(buf, 8, altitude);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
+#endif
+#else
+ mavlink_gps_global_origin_t *packet = (mavlink_gps_global_origin_t *)msgbuf;
+ packet->latitude = latitude;
+ packet->longitude = longitude;
+ packet->altitude = altitude;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h
index 485d8a4afc..362e2d7b9a 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h
@@ -173,6 +173,42 @@ static inline void mavlink_msg_gps_inject_data_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_gps_inject_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, len);
+ _mav_put_uint8_t_array(buf, 3, data, 110);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
+#endif
+#else
+ mavlink_gps_inject_data_t *packet = (mavlink_gps_inject_data_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->len = len;
+ mav_array_memcpy(packet->data, data, sizeof(uint8_t)*110);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE GPS_INJECT_DATA UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h
index a105f8cdad..b539962069 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h
@@ -245,6 +245,56 @@ static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t
#endif
}
+#if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lon);
+ _mav_put_int32_t(buf, 16, alt);
+ _mav_put_uint16_t(buf, 20, eph);
+ _mav_put_uint16_t(buf, 22, epv);
+ _mav_put_uint16_t(buf, 24, vel);
+ _mav_put_uint16_t(buf, 26, cog);
+ _mav_put_uint8_t(buf, 28, fix_type);
+ _mav_put_uint8_t(buf, 29, satellites_visible);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
+#endif
+#else
+ mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt = alt;
+ packet->eph = eph;
+ packet->epv = epv;
+ packet->vel = vel;
+ packet->cog = cog;
+ packet->fix_type = fix_type;
+ packet->satellites_visible = satellites_visible;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE GPS_RAW_INT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h
index 28d6b57d19..10659d0dd8 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h
@@ -199,6 +199,46 @@ static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t s
#endif
}
+#if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, satellites_visible);
+ _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
+ _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
+ _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
+ _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
+ _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
+#endif
+#else
+ mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf;
+ packet->satellites_visible = satellites_visible;
+ mav_array_memcpy(packet->satellite_prn, satellite_prn, sizeof(uint8_t)*20);
+ mav_array_memcpy(packet->satellite_used, satellite_used, sizeof(uint8_t)*20);
+ mav_array_memcpy(packet->satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
+ mav_array_memcpy(packet->satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
+ mav_array_memcpy(packet->satellite_snr, satellite_snr, sizeof(uint8_t)*20);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE GPS_STATUS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h
index 826138fad1..902e381ca8 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h
@@ -198,6 +198,48 @@ static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t ty
#endif
}
+#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, custom_mode);
+ _mav_put_uint8_t(buf, 4, type);
+ _mav_put_uint8_t(buf, 5, autopilot);
+ _mav_put_uint8_t(buf, 6, base_mode);
+ _mav_put_uint8_t(buf, 7, system_status);
+ _mav_put_uint8_t(buf, 8, 3);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
+#endif
+#else
+ mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf;
+ packet->custom_mode = custom_mode;
+ packet->type = type;
+ packet->autopilot = autopilot;
+ packet->base_mode = base_mode;
+ packet->system_status = system_status;
+ packet->mavlink_version = 3;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE HEARTBEAT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h
index 0dcd95ed32..2749cb097f 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h
@@ -300,6 +300,66 @@ static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t
#endif
}
+#if MAVLINK_MSG_ID_HIGHRES_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, xacc);
+ _mav_put_float(buf, 12, yacc);
+ _mav_put_float(buf, 16, zacc);
+ _mav_put_float(buf, 20, xgyro);
+ _mav_put_float(buf, 24, ygyro);
+ _mav_put_float(buf, 28, zgyro);
+ _mav_put_float(buf, 32, xmag);
+ _mav_put_float(buf, 36, ymag);
+ _mav_put_float(buf, 40, zmag);
+ _mav_put_float(buf, 44, abs_pressure);
+ _mav_put_float(buf, 48, diff_pressure);
+ _mav_put_float(buf, 52, pressure_alt);
+ _mav_put_float(buf, 56, temperature);
+ _mav_put_uint16_t(buf, 60, fields_updated);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
+#endif
+#else
+ mavlink_highres_imu_t *packet = (mavlink_highres_imu_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->xacc = xacc;
+ packet->yacc = yacc;
+ packet->zacc = zacc;
+ packet->xgyro = xgyro;
+ packet->ygyro = ygyro;
+ packet->zgyro = zgyro;
+ packet->xmag = xmag;
+ packet->ymag = ymag;
+ packet->zmag = zmag;
+ packet->abs_pressure = abs_pressure;
+ packet->diff_pressure = diff_pressure;
+ packet->pressure_alt = pressure_alt;
+ packet->temperature = temperature;
+ packet->fields_updated = fields_updated;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE HIGHRES_IMU UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h
index aed5108d05..f7507b1cf7 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h
@@ -256,6 +256,58 @@ static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_
#endif
}
+#if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, roll_ailerons);
+ _mav_put_float(buf, 12, pitch_elevator);
+ _mav_put_float(buf, 16, yaw_rudder);
+ _mav_put_float(buf, 20, throttle);
+ _mav_put_float(buf, 24, aux1);
+ _mav_put_float(buf, 28, aux2);
+ _mav_put_float(buf, 32, aux3);
+ _mav_put_float(buf, 36, aux4);
+ _mav_put_uint8_t(buf, 40, mode);
+ _mav_put_uint8_t(buf, 41, nav_mode);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
+#endif
+#else
+ mavlink_hil_controls_t *packet = (mavlink_hil_controls_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->roll_ailerons = roll_ailerons;
+ packet->pitch_elevator = pitch_elevator;
+ packet->yaw_rudder = yaw_rudder;
+ packet->throttle = throttle;
+ packet->aux1 = aux1;
+ packet->aux2 = aux2;
+ packet->aux3 = aux3;
+ packet->aux4 = aux4;
+ packet->mode = mode;
+ packet->nav_mode = nav_mode;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE HIL_CONTROLS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h
index 91aec5b08c..a22c0472f0 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h
@@ -278,6 +278,62 @@ static inline void mavlink_msg_hil_gps_send(mavlink_channel_t chan, uint64_t tim
#endif
}
+#if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lon);
+ _mav_put_int32_t(buf, 16, alt);
+ _mav_put_uint16_t(buf, 20, eph);
+ _mav_put_uint16_t(buf, 22, epv);
+ _mav_put_uint16_t(buf, 24, vel);
+ _mav_put_int16_t(buf, 26, vn);
+ _mav_put_int16_t(buf, 28, ve);
+ _mav_put_int16_t(buf, 30, vd);
+ _mav_put_uint16_t(buf, 32, cog);
+ _mav_put_uint8_t(buf, 34, fix_type);
+ _mav_put_uint8_t(buf, 35, satellites_visible);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
+#endif
+#else
+ mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt = alt;
+ packet->eph = eph;
+ packet->epv = epv;
+ packet->vel = vel;
+ packet->vn = vn;
+ packet->ve = ve;
+ packet->vd = vd;
+ packet->cog = cog;
+ packet->fix_type = fix_type;
+ packet->satellites_visible = satellites_visible;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE HIL_GPS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h
index acb1392e14..eaadf24359 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h
@@ -223,6 +223,52 @@ static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uin
#endif
}
+#if MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, flow_comp_m_x);
+ _mav_put_float(buf, 12, flow_comp_m_y);
+ _mav_put_float(buf, 16, ground_distance);
+ _mav_put_int16_t(buf, 20, flow_x);
+ _mav_put_int16_t(buf, 22, flow_y);
+ _mav_put_uint8_t(buf, 24, sensor_id);
+ _mav_put_uint8_t(buf, 25, quality);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
+#endif
+#else
+ mavlink_hil_optical_flow_t *packet = (mavlink_hil_optical_flow_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->flow_comp_m_x = flow_comp_m_x;
+ packet->flow_comp_m_y = flow_comp_m_y;
+ packet->ground_distance = ground_distance;
+ packet->flow_x = flow_x;
+ packet->flow_y = flow_y;
+ packet->sensor_id = sensor_id;
+ packet->quality = quality;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE HIL_OPTICAL_FLOW UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h
index a42bde50b2..227cd9d94e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h
@@ -289,6 +289,64 @@ static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_hil_rc_inputs_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, 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, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint16_t(buf, 8, chan1_raw);
+ _mav_put_uint16_t(buf, 10, chan2_raw);
+ _mav_put_uint16_t(buf, 12, chan3_raw);
+ _mav_put_uint16_t(buf, 14, chan4_raw);
+ _mav_put_uint16_t(buf, 16, chan5_raw);
+ _mav_put_uint16_t(buf, 18, chan6_raw);
+ _mav_put_uint16_t(buf, 20, chan7_raw);
+ _mav_put_uint16_t(buf, 22, chan8_raw);
+ _mav_put_uint16_t(buf, 24, chan9_raw);
+ _mav_put_uint16_t(buf, 26, chan10_raw);
+ _mav_put_uint16_t(buf, 28, chan11_raw);
+ _mav_put_uint16_t(buf, 30, chan12_raw);
+ _mav_put_uint8_t(buf, 32, rssi);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
+#endif
+#else
+ mavlink_hil_rc_inputs_raw_t *packet = (mavlink_hil_rc_inputs_raw_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->chan1_raw = chan1_raw;
+ packet->chan2_raw = chan2_raw;
+ packet->chan3_raw = chan3_raw;
+ packet->chan4_raw = chan4_raw;
+ packet->chan5_raw = chan5_raw;
+ packet->chan6_raw = chan6_raw;
+ packet->chan7_raw = chan7_raw;
+ packet->chan8_raw = chan8_raw;
+ packet->chan9_raw = chan9_raw;
+ packet->chan10_raw = chan10_raw;
+ packet->chan11_raw = chan11_raw;
+ packet->chan12_raw = chan12_raw;
+ packet->rssi = rssi;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE HIL_RC_INPUTS_RAW UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h
index 6c2667473d..8672f8b8a3 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h
@@ -300,6 +300,66 @@ static inline void mavlink_msg_hil_sensor_send(mavlink_channel_t chan, uint64_t
#endif
}
+#if MAVLINK_MSG_ID_HIL_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, xacc);
+ _mav_put_float(buf, 12, yacc);
+ _mav_put_float(buf, 16, zacc);
+ _mav_put_float(buf, 20, xgyro);
+ _mav_put_float(buf, 24, ygyro);
+ _mav_put_float(buf, 28, zgyro);
+ _mav_put_float(buf, 32, xmag);
+ _mav_put_float(buf, 36, ymag);
+ _mav_put_float(buf, 40, zmag);
+ _mav_put_float(buf, 44, abs_pressure);
+ _mav_put_float(buf, 48, diff_pressure);
+ _mav_put_float(buf, 52, pressure_alt);
+ _mav_put_float(buf, 56, temperature);
+ _mav_put_uint32_t(buf, 60, fields_updated);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
+#endif
+#else
+ mavlink_hil_sensor_t *packet = (mavlink_hil_sensor_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->xacc = xacc;
+ packet->yacc = yacc;
+ packet->zacc = zacc;
+ packet->xgyro = xgyro;
+ packet->ygyro = ygyro;
+ packet->zgyro = zgyro;
+ packet->xmag = xmag;
+ packet->ymag = ymag;
+ packet->zmag = zmag;
+ packet->abs_pressure = abs_pressure;
+ packet->diff_pressure = diff_pressure;
+ packet->pressure_alt = pressure_alt;
+ packet->temperature = temperature;
+ packet->fields_updated = fields_updated;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE HIL_SENSOR UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h
index bcc8577670..923ed60b95 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h
@@ -311,6 +311,68 @@ static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t t
#endif
}
+#if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, roll);
+ _mav_put_float(buf, 12, pitch);
+ _mav_put_float(buf, 16, yaw);
+ _mav_put_float(buf, 20, rollspeed);
+ _mav_put_float(buf, 24, pitchspeed);
+ _mav_put_float(buf, 28, yawspeed);
+ _mav_put_int32_t(buf, 32, lat);
+ _mav_put_int32_t(buf, 36, lon);
+ _mav_put_int32_t(buf, 40, alt);
+ _mav_put_int16_t(buf, 44, vx);
+ _mav_put_int16_t(buf, 46, vy);
+ _mav_put_int16_t(buf, 48, vz);
+ _mav_put_int16_t(buf, 50, xacc);
+ _mav_put_int16_t(buf, 52, yacc);
+ _mav_put_int16_t(buf, 54, zacc);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN);
+#endif
+#else
+ mavlink_hil_state_t *packet = (mavlink_hil_state_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->rollspeed = rollspeed;
+ packet->pitchspeed = pitchspeed;
+ packet->yawspeed = yawspeed;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt = alt;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->xacc = xacc;
+ packet->yacc = yacc;
+ packet->zacc = zacc;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE HIL_STATE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h
index 732176193e..1a028bdf99 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h
@@ -305,6 +305,66 @@ static inline void mavlink_msg_hil_state_quaternion_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 24, rollspeed);
+ _mav_put_float(buf, 28, pitchspeed);
+ _mav_put_float(buf, 32, yawspeed);
+ _mav_put_int32_t(buf, 36, lat);
+ _mav_put_int32_t(buf, 40, lon);
+ _mav_put_int32_t(buf, 44, alt);
+ _mav_put_int16_t(buf, 48, vx);
+ _mav_put_int16_t(buf, 50, vy);
+ _mav_put_int16_t(buf, 52, vz);
+ _mav_put_uint16_t(buf, 54, ind_airspeed);
+ _mav_put_uint16_t(buf, 56, true_airspeed);
+ _mav_put_int16_t(buf, 58, xacc);
+ _mav_put_int16_t(buf, 60, yacc);
+ _mav_put_int16_t(buf, 62, zacc);
+ _mav_put_float_array(buf, 8, attitude_quaternion, 4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
+#endif
+#else
+ mavlink_hil_state_quaternion_t *packet = (mavlink_hil_state_quaternion_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->rollspeed = rollspeed;
+ packet->pitchspeed = pitchspeed;
+ packet->yawspeed = yawspeed;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt = alt;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->ind_airspeed = ind_airspeed;
+ packet->true_airspeed = true_airspeed;
+ packet->xacc = xacc;
+ packet->yacc = yacc;
+ packet->zacc = zacc;
+ mav_array_memcpy(packet->attitude_quaternion, attitude_quaternion, sizeof(float)*4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE HIL_STATE_QUATERNION UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h
index a0b72c0e1e..e18a948695 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, u
#endif
}
+#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
+#endif
+#else
+ mavlink_local_position_ned_t *packet = (mavlink_local_position_ned_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LOCAL_POSITION_NED UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h
index 8c46862027..af7d195b01 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_local_position_ned_system_global_offset_send(mavl
#endif
}
+#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_local_position_ned_system_global_offset_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, roll);
+ _mav_put_float(buf, 20, pitch);
+ _mav_put_float(buf, 24, yaw);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
+#endif
+#else
+ mavlink_local_position_ned_system_global_offset_t *packet = (mavlink_local_position_ned_system_global_offset_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h
index 1794815f8e..8dae721beb 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t ch
#endif
}
+#if MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_local_position_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t coordinate_frame, float x, float y, float z, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, x);
+ _mav_put_float(buf, 4, y);
+ _mav_put_float(buf, 8, z);
+ _mav_put_float(buf, 12, yaw);
+ _mav_put_uint8_t(buf, 16, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN);
+#endif
+#else
+ mavlink_local_position_setpoint_t *packet = (mavlink_local_position_setpoint_t *)msgbuf;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->yaw = yaw;
+ packet->coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h
index 1cf5d15e48..48641f3eb0 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h
@@ -173,6 +173,42 @@ static inline void mavlink_msg_log_data_send(mavlink_channel_t chan, uint16_t id
#endif
}
+#if MAVLINK_MSG_ID_LOG_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_log_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, ofs);
+ _mav_put_uint16_t(buf, 4, id);
+ _mav_put_uint8_t(buf, 6, count);
+ _mav_put_uint8_t_array(buf, 7, data, 90);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
+#endif
+#else
+ mavlink_log_data_t *packet = (mavlink_log_data_t *)msgbuf;
+ packet->ofs = ofs;
+ packet->id = id;
+ packet->count = count;
+ mav_array_memcpy(packet->data, data, sizeof(uint8_t)*90);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LOG_DATA UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h
index 681d8f07cd..8ecaec3ae2 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_log_entry_send(mavlink_channel_t chan, uint16_t i
#endif
}
+#if MAVLINK_MSG_ID_LOG_ENTRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_log_entry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_utc);
+ _mav_put_uint32_t(buf, 4, size);
+ _mav_put_uint16_t(buf, 8, id);
+ _mav_put_uint16_t(buf, 10, num_logs);
+ _mav_put_uint16_t(buf, 12, last_log_num);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
+#endif
+#else
+ mavlink_log_entry_t *packet = (mavlink_log_entry_t *)msgbuf;
+ packet->time_utc = time_utc;
+ packet->size = size;
+ packet->id = id;
+ packet->num_logs = num_logs;
+ packet->last_log_num = last_log_num;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LOG_ENTRY UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h
index feafeaf164..957c4d4cc0 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_log_erase_send(mavlink_channel_t chan, uint8_t ta
#endif
}
+#if MAVLINK_MSG_ID_LOG_ERASE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_log_erase_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN);
+#endif
+#else
+ mavlink_log_erase_t *packet = (mavlink_log_erase_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LOG_ERASE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h
index 5be9eea471..ef5cbb67cb 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uin
#endif
}
+#if MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, ofs);
+ _mav_put_uint32_t(buf, 4, count);
+ _mav_put_uint16_t(buf, 8, id);
+ _mav_put_uint8_t(buf, 10, target_system);
+ _mav_put_uint8_t(buf, 11, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
+#endif
+#else
+ mavlink_log_request_data_t *packet = (mavlink_log_request_data_t *)msgbuf;
+ packet->ofs = ofs;
+ packet->count = count;
+ packet->id = id;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LOG_REQUEST_DATA UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h
index 48a5a03b4c..23fcca29f7 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_log_request_end_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_LOG_REQUEST_END_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_log_request_end_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
+#endif
+#else
+ mavlink_log_request_end_t *packet = (mavlink_log_request_end_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LOG_REQUEST_END UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h
index 7a5b25c171..e511b53125 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_log_request_list_send(mavlink_channel_t chan, uin
#endif
}
+#if MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_log_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, start);
+ _mav_put_uint16_t(buf, 2, end);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
+#endif
+#else
+ mavlink_log_request_list_t *packet = (mavlink_log_request_list_t *)msgbuf;
+ packet->start = start;
+ packet->end = end;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LOG_REQUEST_LIST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h
index 6b6e9e148a..e93b759d0a 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8
#endif
}
+#if MAVLINK_MSG_ID_MANUAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_manual_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int16_t(buf, 0, x);
+ _mav_put_int16_t(buf, 2, y);
+ _mav_put_int16_t(buf, 4, z);
+ _mav_put_int16_t(buf, 6, r);
+ _mav_put_uint16_t(buf, 8, buttons);
+ _mav_put_uint8_t(buf, 10, target);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
+#endif
+#else
+ mavlink_manual_control_t *packet = (mavlink_manual_control_t *)msgbuf;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->r = r;
+ packet->buttons = buttons;
+ packet->target = target;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MANUAL_CONTROL UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h
index a694947c12..b276267269 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_manual_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, roll);
+ _mav_put_float(buf, 8, pitch);
+ _mav_put_float(buf, 12, yaw);
+ _mav_put_float(buf, 16, thrust);
+ _mav_put_uint8_t(buf, 20, mode_switch);
+ _mav_put_uint8_t(buf, 21, manual_override_switch);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
+#endif
+#else
+ mavlink_manual_setpoint_t *packet = (mavlink_manual_setpoint_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->thrust = thrust;
+ packet->mode_switch = mode_switch;
+ packet->manual_override_switch = manual_override_switch;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MANUAL_SETPOINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h
index 5f79329c25..2eb60cc0e6 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h
@@ -173,6 +173,42 @@ static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t
#endif
}
+#if MAVLINK_MSG_ID_MEMORY_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_memory_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, address);
+ _mav_put_uint8_t(buf, 2, ver);
+ _mav_put_uint8_t(buf, 3, type);
+ _mav_put_int8_t_array(buf, 4, value, 32);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
+#endif
+#else
+ mavlink_memory_vect_t *packet = (mavlink_memory_vect_t *)msgbuf;
+ packet->address = address;
+ packet->ver = ver;
+ packet->type = type;
+ mav_array_memcpy(packet->value, value, sizeof(int8_t)*32);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MEMORY_VECT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h
index 7421d8394a..43afd00f7e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t
#endif
}
+#if MAVLINK_MSG_ID_MISSION_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, type);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN);
+#endif
+#else
+ mavlink_mission_ack_t *packet = (mavlink_mission_ack_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->type = type;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_ACK UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h
index 8f441c8e5c..120986873f 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_clear_all_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
+#endif
+#else
+ mavlink_mission_clear_all_t *packet = (mavlink_mission_clear_all_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_CLEAR_ALL UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h
index eac7793067..7e4748eaef 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_
#endif
}
+#if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, count);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
+#endif
+#else
+ mavlink_mission_count_t *packet = (mavlink_mission_count_t *)msgbuf;
+ packet->count = count;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_COUNT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h
index dbcdbd3f9c..201b7a6fb4 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h
@@ -146,6 +146,38 @@ static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_MISSION_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, seq);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
+#endif
+#else
+ mavlink_mission_current_t *packet = (mavlink_mission_current_t *)msgbuf;
+ packet->seq = seq;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_CURRENT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h
index a8d60eca7e..ef9394f00c 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h
@@ -289,6 +289,64 @@ static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t
#endif
}
+#if MAVLINK_MSG_ID_MISSION_ITEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, param1);
+ _mav_put_float(buf, 4, param2);
+ _mav_put_float(buf, 8, param3);
+ _mav_put_float(buf, 12, param4);
+ _mav_put_float(buf, 16, x);
+ _mav_put_float(buf, 20, y);
+ _mav_put_float(buf, 24, z);
+ _mav_put_uint16_t(buf, 28, seq);
+ _mav_put_uint16_t(buf, 30, command);
+ _mav_put_uint8_t(buf, 32, target_system);
+ _mav_put_uint8_t(buf, 33, target_component);
+ _mav_put_uint8_t(buf, 34, frame);
+ _mav_put_uint8_t(buf, 35, current);
+ _mav_put_uint8_t(buf, 36, autocontinue);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
+#endif
+#else
+ mavlink_mission_item_t *packet = (mavlink_mission_item_t *)msgbuf;
+ packet->param1 = param1;
+ packet->param2 = param2;
+ packet->param3 = param3;
+ packet->param4 = param4;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->seq = seq;
+ packet->command = command;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->frame = frame;
+ packet->current = current;
+ packet->autocontinue = autocontinue;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_ITEM UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h
index f3744fde6c..9dfa280433 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h
@@ -146,6 +146,38 @@ static inline void mavlink_msg_mission_item_reached_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_item_reached_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, seq);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
+#endif
+#else
+ mavlink_mission_item_reached_t *packet = (mavlink_mission_item_reached_t *)msgbuf;
+ packet->seq = seq;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_ITEM_REACHED UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h
index ac84e35540..29b0ef6ef5 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, seq);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
+#endif
+#else
+ mavlink_mission_request_t *packet = (mavlink_mission_request_t *)msgbuf;
+ packet->seq = seq;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_REQUEST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h
index d999babdbd..a275348acc 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
+#endif
+#else
+ mavlink_mission_request_list_t *packet = (mavlink_mission_request_list_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_REQUEST_LIST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h
index 35c7e12856..79a88dc084 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel
#endif
}
+#if MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int16_t(buf, 0, start_index);
+ _mav_put_int16_t(buf, 2, end_index);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
+#endif
+#else
+ mavlink_mission_request_partial_list_t *packet = (mavlink_mission_request_partial_list_t *)msgbuf;
+ packet->start_index = start_index;
+ packet->end_index = end_index;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_REQUEST_PARTIAL_LIST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h
index 63b37cf8c8..0c2a3ada4e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_mission_set_current_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_set_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, seq);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
+#endif
+#else
+ mavlink_mission_set_current_t *packet = (mavlink_mission_set_current_t *)msgbuf;
+ packet->seq = seq;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_SET_CURRENT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h
index 7de38bd7b5..17a5a6bdd8 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t
#endif
}
+#if MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int16_t(buf, 0, start_index);
+ _mav_put_int16_t(buf, 2, end_index);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
+#endif
+#else
+ mavlink_mission_write_partial_list_t *packet = (mavlink_mission_write_partial_list_t *)msgbuf;
+ packet->start_index = start_index;
+ packet->end_index = end_index;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MISSION_WRITE_PARTIAL_LIST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h
index fbf4f75c95..df82704a4b 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h
@@ -162,6 +162,40 @@ static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_named_value_float_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, value);
+ _mav_put_char_array(buf, 8, name, 10);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
+#endif
+#else
+ mavlink_named_value_float_t *packet = (mavlink_named_value_float_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->value = value;
+ mav_array_memcpy(packet->name, name, sizeof(char)*10);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE NAMED_VALUE_FLOAT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h
index 052f247935..cfdd73d61e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h
@@ -162,6 +162,40 @@ static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_named_value_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, value);
+ _mav_put_char_array(buf, 8, name, 10);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
+#endif
+#else
+ mavlink_named_value_int_t *packet = (mavlink_named_value_int_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->value = value;
+ mav_array_memcpy(packet->name, name, sizeof(char)*10);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE NAMED_VALUE_INT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h
index e95c144de7..b9a748b222 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h
@@ -223,6 +223,52 @@ static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan
#endif
}
+#if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, nav_roll);
+ _mav_put_float(buf, 4, nav_pitch);
+ _mav_put_float(buf, 8, alt_error);
+ _mav_put_float(buf, 12, aspd_error);
+ _mav_put_float(buf, 16, xtrack_error);
+ _mav_put_int16_t(buf, 20, nav_bearing);
+ _mav_put_int16_t(buf, 22, target_bearing);
+ _mav_put_uint16_t(buf, 24, wp_dist);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
+#endif
+#else
+ mavlink_nav_controller_output_t *packet = (mavlink_nav_controller_output_t *)msgbuf;
+ packet->nav_roll = nav_roll;
+ packet->nav_pitch = nav_pitch;
+ packet->alt_error = alt_error;
+ packet->aspd_error = aspd_error;
+ packet->xtrack_error = xtrack_error;
+ packet->nav_bearing = nav_bearing;
+ packet->target_bearing = target_bearing;
+ packet->wp_dist = wp_dist;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h
index 4debb6e663..4ee9c452fb 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h
@@ -196,6 +196,46 @@ static inline void mavlink_msg_omnidirectional_flow_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_omnidirectional_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, const int16_t *left, const int16_t *right, uint8_t quality, float front_distance_m)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, front_distance_m);
+ _mav_put_uint8_t(buf, 52, sensor_id);
+ _mav_put_uint8_t(buf, 53, quality);
+ _mav_put_int16_t_array(buf, 12, left, 10);
+ _mav_put_int16_t_array(buf, 32, right, 10);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
+#endif
+#else
+ mavlink_omnidirectional_flow_t *packet = (mavlink_omnidirectional_flow_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->front_distance_m = front_distance_m;
+ packet->sensor_id = sensor_id;
+ packet->quality = quality;
+ mav_array_memcpy(packet->left, left, sizeof(int16_t)*10);
+ mav_array_memcpy(packet->right, right, sizeof(int16_t)*10);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE OMNIDIRECTIONAL_FLOW UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h
index cf6db9147e..6a2efc664f 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h
@@ -223,6 +223,52 @@ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_
#endif
}
+#if MAVLINK_MSG_ID_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, flow_comp_m_x);
+ _mav_put_float(buf, 12, flow_comp_m_y);
+ _mav_put_float(buf, 16, ground_distance);
+ _mav_put_int16_t(buf, 20, flow_x);
+ _mav_put_int16_t(buf, 22, flow_y);
+ _mav_put_uint8_t(buf, 24, sensor_id);
+ _mav_put_uint8_t(buf, 25, quality);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
+#endif
+#else
+ mavlink_optical_flow_t *packet = (mavlink_optical_flow_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->flow_comp_m_x = flow_comp_m_x;
+ packet->flow_comp_m_y = flow_comp_m_y;
+ packet->ground_distance = ground_distance;
+ packet->flow_x = flow_x;
+ packet->flow_y = flow_y;
+ packet->sensor_id = sensor_id;
+ packet->quality = quality;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE OPTICAL_FLOW UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h
index 39e0072741..f9466b002e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, u
#endif
}
+#if MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_param_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
+#endif
+#else
+ mavlink_param_request_list_t *packet = (mavlink_param_request_list_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE PARAM_REQUEST_LIST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h
index 5d9113114b..730cff0669 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h
@@ -173,6 +173,42 @@ static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, u
#endif
}
+#if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_param_request_read_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int16_t(buf, 0, param_index);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_char_array(buf, 4, param_id, 16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
+#endif
+#else
+ mavlink_param_request_read_t *packet = (mavlink_param_request_read_t *)msgbuf;
+ packet->param_index = param_index;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE PARAM_REQUEST_READ UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h
index 1bd1f00596..f669af1a25 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h
@@ -184,6 +184,44 @@ static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t ta
#endif
}
+#if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, param_value);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 22, param_type);
+ _mav_put_char_array(buf, 6, param_id, 16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
+#endif
+#else
+ mavlink_param_set_t *packet = (mavlink_param_set_t *)msgbuf;
+ packet->param_value = param_value;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->param_type = param_type;
+ mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE PARAM_SET UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h
index 17c759811f..c27957913f 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h
@@ -184,6 +184,44 @@ static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const ch
#endif
}
+#if MAVLINK_MSG_ID_PARAM_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_param_value_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, param_value);
+ _mav_put_uint16_t(buf, 4, param_count);
+ _mav_put_uint16_t(buf, 6, param_index);
+ _mav_put_uint8_t(buf, 24, param_type);
+ _mav_put_char_array(buf, 8, param_id, 16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
+#endif
+#else
+ mavlink_param_value_t *packet = (mavlink_param_value_t *)msgbuf;
+ packet->param_value = param_value;
+ packet->param_count = param_count;
+ packet->param_index = param_index;
+ packet->param_type = param_type;
+ mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE PARAM_VALUE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h
index 0c68ca1765..b1501ba1f8 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_u
#endif
}
+#if MAVLINK_MSG_ID_PING_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint32_t(buf, 8, seq);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN);
+#endif
+#else
+ mavlink_ping_t *packet = (mavlink_ping_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->seq = seq;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE PING UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_power_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_power_status.h
new file mode 100644
index 0000000000..1a6259aa3d
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_power_status.h
@@ -0,0 +1,257 @@
+// MESSAGE POWER_STATUS PACKING
+
+#define MAVLINK_MSG_ID_POWER_STATUS 125
+
+typedef struct __mavlink_power_status_t
+{
+ uint16_t Vcc; ///< 5V rail voltage in millivolts
+ uint16_t Vservo; ///< servo rail voltage in millivolts
+ uint16_t flags; ///< power supply status flags (see MAV_POWER_STATUS enum)
+} mavlink_power_status_t;
+
+#define MAVLINK_MSG_ID_POWER_STATUS_LEN 6
+#define MAVLINK_MSG_ID_125_LEN 6
+
+#define MAVLINK_MSG_ID_POWER_STATUS_CRC 203
+#define MAVLINK_MSG_ID_125_CRC 203
+
+
+
+#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \
+ "POWER_STATUS", \
+ 3, \
+ { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \
+ { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a power_status message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param Vcc 5V rail voltage in millivolts
+ * @param Vservo servo rail voltage in millivolts
+ * @param flags power supply status flags (see MAV_POWER_STATUS enum)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t Vcc, uint16_t Vservo, uint16_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, Vcc);
+ _mav_put_uint16_t(buf, 2, Vservo);
+ _mav_put_uint16_t(buf, 4, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#else
+ mavlink_power_status_t packet;
+ packet.Vcc = Vcc;
+ packet.Vservo = Vservo;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_POWER_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a power_status message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param Vcc 5V rail voltage in millivolts
+ * @param Vservo servo rail voltage in millivolts
+ * @param flags power supply status flags (see MAV_POWER_STATUS enum)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t Vcc,uint16_t Vservo,uint16_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, Vcc);
+ _mav_put_uint16_t(buf, 2, Vservo);
+ _mav_put_uint16_t(buf, 4, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#else
+ mavlink_power_status_t packet;
+ packet.Vcc = Vcc;
+ packet.Vservo = Vservo;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_POWER_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a power_status struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param power_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_power_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_power_status_t* power_status)
+{
+ return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->Vcc, power_status->Vservo, power_status->flags);
+}
+
+/**
+ * @brief Encode a power_status struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param power_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_power_status_t* power_status)
+{
+ return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->Vcc, power_status->Vservo, power_status->flags);
+}
+
+/**
+ * @brief Send a power_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param Vcc 5V rail voltage in millivolts
+ * @param Vservo servo rail voltage in millivolts
+ * @param flags power supply status flags (see MAV_POWER_STATUS enum)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_power_status_send(mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, Vcc);
+ _mav_put_uint16_t(buf, 2, Vservo);
+ _mav_put_uint16_t(buf, 4, flags);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#endif
+#else
+ mavlink_power_status_t packet;
+ packet.Vcc = Vcc;
+ packet.Vservo = Vservo;
+ packet.flags = flags;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_POWER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_power_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, Vcc);
+ _mav_put_uint16_t(buf, 2, Vservo);
+ _mav_put_uint16_t(buf, 4, flags);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#endif
+#else
+ mavlink_power_status_t *packet = (mavlink_power_status_t *)msgbuf;
+ packet->Vcc = Vcc;
+ packet->Vservo = Vservo;
+ packet->flags = flags;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE POWER_STATUS UNPACKING
+
+
+/**
+ * @brief Get field Vcc from power_status message
+ *
+ * @return 5V rail voltage in millivolts
+ */
+static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field Vservo from power_status message
+ *
+ * @return servo rail voltage in millivolts
+ */
+static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 2);
+}
+
+/**
+ * @brief Get field flags from power_status message
+ *
+ * @return power supply status flags (see MAV_POWER_STATUS enum)
+ */
+static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Decode a power_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param power_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_power_status_decode(const mavlink_message_t* msg, mavlink_power_status_t* power_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ power_status->Vcc = mavlink_msg_power_status_get_Vcc(msg);
+ power_status->Vservo = mavlink_msg_power_status_get_Vservo(msg);
+ power_status->flags = mavlink_msg_power_status_get_flags(msg);
+#else
+ memcpy(power_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POWER_STATUS_LEN);
+#endif
+}
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h
index fceb7d1688..5763008fe2 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_radio_status_send(mavlink_channel_t chan, uint8_t
#endif
}
+#if MAVLINK_MSG_ID_RADIO_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_radio_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, rxerrors);
+ _mav_put_uint16_t(buf, 2, fixed);
+ _mav_put_uint8_t(buf, 4, rssi);
+ _mav_put_uint8_t(buf, 5, remrssi);
+ _mav_put_uint8_t(buf, 6, txbuf);
+ _mav_put_uint8_t(buf, 7, noise);
+ _mav_put_uint8_t(buf, 8, remnoise);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
+#endif
+#else
+ mavlink_radio_status_t *packet = (mavlink_radio_status_t *)msgbuf;
+ packet->rxerrors = rxerrors;
+ packet->fixed = fixed;
+ packet->rssi = rssi;
+ packet->remrssi = remrssi;
+ packet->txbuf = txbuf;
+ packet->noise = noise;
+ packet->remnoise = remnoise;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RADIO_STATUS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h
index 62a9b6eeae..a98e8ce721 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h
@@ -245,6 +245,56 @@ static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t tim
#endif
}
+#if MAVLINK_MSG_ID_RAW_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_int16_t(buf, 8, xacc);
+ _mav_put_int16_t(buf, 10, yacc);
+ _mav_put_int16_t(buf, 12, zacc);
+ _mav_put_int16_t(buf, 14, xgyro);
+ _mav_put_int16_t(buf, 16, ygyro);
+ _mav_put_int16_t(buf, 18, zgyro);
+ _mav_put_int16_t(buf, 20, xmag);
+ _mav_put_int16_t(buf, 22, ymag);
+ _mav_put_int16_t(buf, 24, zmag);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN);
+#endif
+#else
+ mavlink_raw_imu_t *packet = (mavlink_raw_imu_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->xacc = xacc;
+ packet->yacc = yacc;
+ packet->zacc = zacc;
+ packet->xgyro = xgyro;
+ packet->ygyro = ygyro;
+ packet->zgyro = zgyro;
+ packet->xmag = xmag;
+ packet->ymag = ymag;
+ packet->zmag = zmag;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RAW_IMU UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h
index 82c5fad4ab..6bd37fcaee 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_
#endif
}
+#if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_raw_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_int16_t(buf, 8, press_abs);
+ _mav_put_int16_t(buf, 10, press_diff1);
+ _mav_put_int16_t(buf, 12, press_diff2);
+ _mav_put_int16_t(buf, 14, temperature);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
+#endif
+#else
+ mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->press_abs = press_abs;
+ packet->press_diff1 = press_diff1;
+ packet->press_diff2 = press_diff2;
+ packet->temperature = temperature;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RAW_PRESSURE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels.h
new file mode 100644
index 0000000000..479af122ff
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels.h
@@ -0,0 +1,689 @@
+// MESSAGE RC_CHANNELS PACKING
+
+#define MAVLINK_MSG_ID_RC_CHANNELS 65
+
+typedef struct __mavlink_rc_channels_t
+{
+ uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
+ uint16_t chan1_raw; ///< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan2_raw; ///< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan3_raw; ///< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan4_raw; ///< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan5_raw; ///< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan6_raw; ///< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan7_raw; ///< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan8_raw; ///< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan9_raw; ///< RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan10_raw; ///< RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan11_raw; ///< RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan12_raw; ///< RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan13_raw; ///< RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan14_raw; ///< RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan15_raw; ///< RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan16_raw; ///< RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan17_raw; ///< RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan18_raw; ///< RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint8_t chancount; ///< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
+ uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
+} mavlink_rc_channels_t;
+
+#define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42
+#define MAVLINK_MSG_ID_65_LEN 42
+
+#define MAVLINK_MSG_ID_RC_CHANNELS_CRC 118
+#define MAVLINK_MSG_ID_65_CRC 118
+
+
+
+#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \
+ "RC_CHANNELS", \
+ 21, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \
+ { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \
+ { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \
+ { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \
+ { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \
+ { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \
+ { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \
+ { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \
+ { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \
+ { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \
+ { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \
+ { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \
+ { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \
+ { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \
+ { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \
+ { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \
+ { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \
+ { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \
+ { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \
+ { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \
+ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a rc_channels message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
+ * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, chan1_raw);
+ _mav_put_uint16_t(buf, 6, chan2_raw);
+ _mav_put_uint16_t(buf, 8, chan3_raw);
+ _mav_put_uint16_t(buf, 10, chan4_raw);
+ _mav_put_uint16_t(buf, 12, chan5_raw);
+ _mav_put_uint16_t(buf, 14, chan6_raw);
+ _mav_put_uint16_t(buf, 16, chan7_raw);
+ _mav_put_uint16_t(buf, 18, chan8_raw);
+ _mav_put_uint16_t(buf, 20, chan9_raw);
+ _mav_put_uint16_t(buf, 22, chan10_raw);
+ _mav_put_uint16_t(buf, 24, chan11_raw);
+ _mav_put_uint16_t(buf, 26, chan12_raw);
+ _mav_put_uint16_t(buf, 28, chan13_raw);
+ _mav_put_uint16_t(buf, 30, chan14_raw);
+ _mav_put_uint16_t(buf, 32, chan15_raw);
+ _mav_put_uint16_t(buf, 34, chan16_raw);
+ _mav_put_uint16_t(buf, 36, chan17_raw);
+ _mav_put_uint16_t(buf, 38, chan18_raw);
+ _mav_put_uint8_t(buf, 40, chancount);
+ _mav_put_uint8_t(buf, 41, rssi);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#else
+ mavlink_rc_channels_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.chan1_raw = chan1_raw;
+ packet.chan2_raw = chan2_raw;
+ packet.chan3_raw = chan3_raw;
+ packet.chan4_raw = chan4_raw;
+ packet.chan5_raw = chan5_raw;
+ packet.chan6_raw = chan6_raw;
+ packet.chan7_raw = chan7_raw;
+ packet.chan8_raw = chan8_raw;
+ packet.chan9_raw = chan9_raw;
+ packet.chan10_raw = chan10_raw;
+ packet.chan11_raw = chan11_raw;
+ packet.chan12_raw = chan12_raw;
+ packet.chan13_raw = chan13_raw;
+ packet.chan14_raw = chan14_raw;
+ packet.chan15_raw = chan15_raw;
+ packet.chan16_raw = chan16_raw;
+ packet.chan17_raw = chan17_raw;
+ packet.chan18_raw = chan18_raw;
+ packet.chancount = chancount;
+ packet.rssi = rssi;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a rc_channels message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
+ * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t chancount,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,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw,uint8_t rssi)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, chan1_raw);
+ _mav_put_uint16_t(buf, 6, chan2_raw);
+ _mav_put_uint16_t(buf, 8, chan3_raw);
+ _mav_put_uint16_t(buf, 10, chan4_raw);
+ _mav_put_uint16_t(buf, 12, chan5_raw);
+ _mav_put_uint16_t(buf, 14, chan6_raw);
+ _mav_put_uint16_t(buf, 16, chan7_raw);
+ _mav_put_uint16_t(buf, 18, chan8_raw);
+ _mav_put_uint16_t(buf, 20, chan9_raw);
+ _mav_put_uint16_t(buf, 22, chan10_raw);
+ _mav_put_uint16_t(buf, 24, chan11_raw);
+ _mav_put_uint16_t(buf, 26, chan12_raw);
+ _mav_put_uint16_t(buf, 28, chan13_raw);
+ _mav_put_uint16_t(buf, 30, chan14_raw);
+ _mav_put_uint16_t(buf, 32, chan15_raw);
+ _mav_put_uint16_t(buf, 34, chan16_raw);
+ _mav_put_uint16_t(buf, 36, chan17_raw);
+ _mav_put_uint16_t(buf, 38, chan18_raw);
+ _mav_put_uint8_t(buf, 40, chancount);
+ _mav_put_uint8_t(buf, 41, rssi);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#else
+ mavlink_rc_channels_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.chan1_raw = chan1_raw;
+ packet.chan2_raw = chan2_raw;
+ packet.chan3_raw = chan3_raw;
+ packet.chan4_raw = chan4_raw;
+ packet.chan5_raw = chan5_raw;
+ packet.chan6_raw = chan6_raw;
+ packet.chan7_raw = chan7_raw;
+ packet.chan8_raw = chan8_raw;
+ packet.chan9_raw = chan9_raw;
+ packet.chan10_raw = chan10_raw;
+ packet.chan11_raw = chan11_raw;
+ packet.chan12_raw = chan12_raw;
+ packet.chan13_raw = chan13_raw;
+ packet.chan14_raw = chan14_raw;
+ packet.chan15_raw = chan15_raw;
+ packet.chan16_raw = chan16_raw;
+ packet.chan17_raw = chan17_raw;
+ packet.chan18_raw = chan18_raw;
+ packet.chancount = chancount;
+ packet.rssi = rssi;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a rc_channels struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param rc_channels C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels)
+{
+ return mavlink_msg_rc_channels_pack(system_id, component_id, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi);
+}
+
+/**
+ * @brief Encode a rc_channels struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param rc_channels C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels)
+{
+ return mavlink_msg_rc_channels_pack_chan(system_id, component_id, chan, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi);
+}
+
+/**
+ * @brief Send a rc_channels message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
+ * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_rc_channels_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, chan1_raw);
+ _mav_put_uint16_t(buf, 6, chan2_raw);
+ _mav_put_uint16_t(buf, 8, chan3_raw);
+ _mav_put_uint16_t(buf, 10, chan4_raw);
+ _mav_put_uint16_t(buf, 12, chan5_raw);
+ _mav_put_uint16_t(buf, 14, chan6_raw);
+ _mav_put_uint16_t(buf, 16, chan7_raw);
+ _mav_put_uint16_t(buf, 18, chan8_raw);
+ _mav_put_uint16_t(buf, 20, chan9_raw);
+ _mav_put_uint16_t(buf, 22, chan10_raw);
+ _mav_put_uint16_t(buf, 24, chan11_raw);
+ _mav_put_uint16_t(buf, 26, chan12_raw);
+ _mav_put_uint16_t(buf, 28, chan13_raw);
+ _mav_put_uint16_t(buf, 30, chan14_raw);
+ _mav_put_uint16_t(buf, 32, chan15_raw);
+ _mav_put_uint16_t(buf, 34, chan16_raw);
+ _mav_put_uint16_t(buf, 36, chan17_raw);
+ _mav_put_uint16_t(buf, 38, chan18_raw);
+ _mav_put_uint8_t(buf, 40, chancount);
+ _mav_put_uint8_t(buf, 41, rssi);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#endif
+#else
+ mavlink_rc_channels_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.chan1_raw = chan1_raw;
+ packet.chan2_raw = chan2_raw;
+ packet.chan3_raw = chan3_raw;
+ packet.chan4_raw = chan4_raw;
+ packet.chan5_raw = chan5_raw;
+ packet.chan6_raw = chan6_raw;
+ packet.chan7_raw = chan7_raw;
+ packet.chan8_raw = chan8_raw;
+ packet.chan9_raw = chan9_raw;
+ packet.chan10_raw = chan10_raw;
+ packet.chan11_raw = chan11_raw;
+ packet.chan12_raw = chan12_raw;
+ packet.chan13_raw = chan13_raw;
+ packet.chan14_raw = chan14_raw;
+ packet.chan15_raw = chan15_raw;
+ packet.chan16_raw = chan16_raw;
+ packet.chan17_raw = chan17_raw;
+ packet.chan18_raw = chan18_raw;
+ packet.chancount = chancount;
+ packet.rssi = rssi;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, chan1_raw);
+ _mav_put_uint16_t(buf, 6, chan2_raw);
+ _mav_put_uint16_t(buf, 8, chan3_raw);
+ _mav_put_uint16_t(buf, 10, chan4_raw);
+ _mav_put_uint16_t(buf, 12, chan5_raw);
+ _mav_put_uint16_t(buf, 14, chan6_raw);
+ _mav_put_uint16_t(buf, 16, chan7_raw);
+ _mav_put_uint16_t(buf, 18, chan8_raw);
+ _mav_put_uint16_t(buf, 20, chan9_raw);
+ _mav_put_uint16_t(buf, 22, chan10_raw);
+ _mav_put_uint16_t(buf, 24, chan11_raw);
+ _mav_put_uint16_t(buf, 26, chan12_raw);
+ _mav_put_uint16_t(buf, 28, chan13_raw);
+ _mav_put_uint16_t(buf, 30, chan14_raw);
+ _mav_put_uint16_t(buf, 32, chan15_raw);
+ _mav_put_uint16_t(buf, 34, chan16_raw);
+ _mav_put_uint16_t(buf, 36, chan17_raw);
+ _mav_put_uint16_t(buf, 38, chan18_raw);
+ _mav_put_uint8_t(buf, 40, chancount);
+ _mav_put_uint8_t(buf, 41, rssi);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#endif
+#else
+ mavlink_rc_channels_t *packet = (mavlink_rc_channels_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->chan1_raw = chan1_raw;
+ packet->chan2_raw = chan2_raw;
+ packet->chan3_raw = chan3_raw;
+ packet->chan4_raw = chan4_raw;
+ packet->chan5_raw = chan5_raw;
+ packet->chan6_raw = chan6_raw;
+ packet->chan7_raw = chan7_raw;
+ packet->chan8_raw = chan8_raw;
+ packet->chan9_raw = chan9_raw;
+ packet->chan10_raw = chan10_raw;
+ packet->chan11_raw = chan11_raw;
+ packet->chan12_raw = chan12_raw;
+ packet->chan13_raw = chan13_raw;
+ packet->chan14_raw = chan14_raw;
+ packet->chan15_raw = chan15_raw;
+ packet->chan16_raw = chan16_raw;
+ packet->chan17_raw = chan17_raw;
+ packet->chan18_raw = chan18_raw;
+ packet->chancount = chancount;
+ packet->rssi = rssi;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE RC_CHANNELS UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from rc_channels message
+ *
+ * @return Timestamp (milliseconds since system boot)
+ */
+static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field chancount from rc_channels message
+ *
+ * @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
+ */
+static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 40);
+}
+
+/**
+ * @brief Get field chan1_raw from rc_channels message
+ *
+ * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field chan2_raw from rc_channels message
+ *
+ * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 6);
+}
+
+/**
+ * @brief Get field chan3_raw from rc_channels message
+ *
+ * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 8);
+}
+
+/**
+ * @brief Get field chan4_raw from rc_channels message
+ *
+ * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 10);
+}
+
+/**
+ * @brief Get field chan5_raw from rc_channels message
+ *
+ * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 12);
+}
+
+/**
+ * @brief Get field chan6_raw from rc_channels message
+ *
+ * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 14);
+}
+
+/**
+ * @brief Get field chan7_raw from rc_channels message
+ *
+ * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 16);
+}
+
+/**
+ * @brief Get field chan8_raw from rc_channels message
+ *
+ * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 18);
+}
+
+/**
+ * @brief Get field chan9_raw from rc_channels message
+ *
+ * @return RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 20);
+}
+
+/**
+ * @brief Get field chan10_raw from rc_channels message
+ *
+ * @return RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 22);
+}
+
+/**
+ * @brief Get field chan11_raw from rc_channels message
+ *
+ * @return RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 24);
+}
+
+/**
+ * @brief Get field chan12_raw from rc_channels message
+ *
+ * @return RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 26);
+}
+
+/**
+ * @brief Get field chan13_raw from rc_channels message
+ *
+ * @return RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 28);
+}
+
+/**
+ * @brief Get field chan14_raw from rc_channels message
+ *
+ * @return RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 30);
+}
+
+/**
+ * @brief Get field chan15_raw from rc_channels message
+ *
+ * @return RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 32);
+}
+
+/**
+ * @brief Get field chan16_raw from rc_channels message
+ *
+ * @return RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 34);
+}
+
+/**
+ * @brief Get field chan17_raw from rc_channels message
+ *
+ * @return RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 36);
+}
+
+/**
+ * @brief Get field chan18_raw from rc_channels message
+ *
+ * @return RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ */
+static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 38);
+}
+
+/**
+ * @brief Get field rssi from rc_channels message
+ *
+ * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
+ */
+static inline uint8_t mavlink_msg_rc_channels_get_rssi(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 41);
+}
+
+/**
+ * @brief Decode a rc_channels message into a struct
+ *
+ * @param msg The message to decode
+ * @param rc_channels C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_rc_channels_decode(const mavlink_message_t* msg, mavlink_rc_channels_t* rc_channels)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ rc_channels->time_boot_ms = mavlink_msg_rc_channels_get_time_boot_ms(msg);
+ rc_channels->chan1_raw = mavlink_msg_rc_channels_get_chan1_raw(msg);
+ rc_channels->chan2_raw = mavlink_msg_rc_channels_get_chan2_raw(msg);
+ rc_channels->chan3_raw = mavlink_msg_rc_channels_get_chan3_raw(msg);
+ rc_channels->chan4_raw = mavlink_msg_rc_channels_get_chan4_raw(msg);
+ rc_channels->chan5_raw = mavlink_msg_rc_channels_get_chan5_raw(msg);
+ rc_channels->chan6_raw = mavlink_msg_rc_channels_get_chan6_raw(msg);
+ rc_channels->chan7_raw = mavlink_msg_rc_channels_get_chan7_raw(msg);
+ rc_channels->chan8_raw = mavlink_msg_rc_channels_get_chan8_raw(msg);
+ rc_channels->chan9_raw = mavlink_msg_rc_channels_get_chan9_raw(msg);
+ rc_channels->chan10_raw = mavlink_msg_rc_channels_get_chan10_raw(msg);
+ rc_channels->chan11_raw = mavlink_msg_rc_channels_get_chan11_raw(msg);
+ rc_channels->chan12_raw = mavlink_msg_rc_channels_get_chan12_raw(msg);
+ rc_channels->chan13_raw = mavlink_msg_rc_channels_get_chan13_raw(msg);
+ rc_channels->chan14_raw = mavlink_msg_rc_channels_get_chan14_raw(msg);
+ rc_channels->chan15_raw = mavlink_msg_rc_channels_get_chan15_raw(msg);
+ rc_channels->chan16_raw = mavlink_msg_rc_channels_get_chan16_raw(msg);
+ rc_channels->chan17_raw = mavlink_msg_rc_channels_get_chan17_raw(msg);
+ rc_channels->chan18_raw = mavlink_msg_rc_channels_get_chan18_raw(msg);
+ rc_channels->chancount = mavlink_msg_rc_channels_get_chancount(msg);
+ rc_channels->rssi = mavlink_msg_rc_channels_get_rssi(msg);
+#else
+ memcpy(rc_channels, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_LEN);
+#endif
+}
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h
index 0d8a1514b1..15d4c6f958 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h
@@ -245,6 +245,56 @@ static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, 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)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, chan1_raw);
+ _mav_put_uint16_t(buf, 2, chan2_raw);
+ _mav_put_uint16_t(buf, 4, chan3_raw);
+ _mav_put_uint16_t(buf, 6, chan4_raw);
+ _mav_put_uint16_t(buf, 8, chan5_raw);
+ _mav_put_uint16_t(buf, 10, chan6_raw);
+ _mav_put_uint16_t(buf, 12, chan7_raw);
+ _mav_put_uint16_t(buf, 14, chan8_raw);
+ _mav_put_uint8_t(buf, 16, target_system);
+ _mav_put_uint8_t(buf, 17, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
+#endif
+#else
+ mavlink_rc_channels_override_t *packet = (mavlink_rc_channels_override_t *)msgbuf;
+ packet->chan1_raw = chan1_raw;
+ packet->chan2_raw = chan2_raw;
+ packet->chan3_raw = chan3_raw;
+ packet->chan4_raw = chan4_raw;
+ packet->chan5_raw = chan5_raw;
+ packet->chan6_raw = chan6_raw;
+ packet->chan7_raw = chan7_raw;
+ packet->chan8_raw = chan8_raw;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h
index 3c0aed0202..d75a5934aa 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h
@@ -256,6 +256,58 @@ static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_rc_channels_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, 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)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, chan1_raw);
+ _mav_put_uint16_t(buf, 6, chan2_raw);
+ _mav_put_uint16_t(buf, 8, chan3_raw);
+ _mav_put_uint16_t(buf, 10, chan4_raw);
+ _mav_put_uint16_t(buf, 12, chan5_raw);
+ _mav_put_uint16_t(buf, 14, chan6_raw);
+ _mav_put_uint16_t(buf, 16, chan7_raw);
+ _mav_put_uint16_t(buf, 18, chan8_raw);
+ _mav_put_uint8_t(buf, 20, port);
+ _mav_put_uint8_t(buf, 21, rssi);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
+#endif
+#else
+ mavlink_rc_channels_raw_t *packet = (mavlink_rc_channels_raw_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->chan1_raw = chan1_raw;
+ packet->chan2_raw = chan2_raw;
+ packet->chan3_raw = chan3_raw;
+ packet->chan4_raw = chan4_raw;
+ packet->chan5_raw = chan5_raw;
+ packet->chan6_raw = chan6_raw;
+ packet->chan7_raw = chan7_raw;
+ packet->chan8_raw = chan8_raw;
+ packet->port = port;
+ packet->rssi = rssi;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RC_CHANNELS_RAW UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
index 2153ab3928..f400f987dd 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
@@ -256,6 +256,58 @@ static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, u
#endif
}
+#if MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_rc_channels_scaled_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, 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)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int16_t(buf, 4, chan1_scaled);
+ _mav_put_int16_t(buf, 6, chan2_scaled);
+ _mav_put_int16_t(buf, 8, chan3_scaled);
+ _mav_put_int16_t(buf, 10, chan4_scaled);
+ _mav_put_int16_t(buf, 12, chan5_scaled);
+ _mav_put_int16_t(buf, 14, chan6_scaled);
+ _mav_put_int16_t(buf, 16, chan7_scaled);
+ _mav_put_int16_t(buf, 18, chan8_scaled);
+ _mav_put_uint8_t(buf, 20, port);
+ _mav_put_uint8_t(buf, 21, rssi);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
+#endif
+#else
+ mavlink_rc_channels_scaled_t *packet = (mavlink_rc_channels_scaled_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->chan1_scaled = chan1_scaled;
+ packet->chan2_scaled = chan2_scaled;
+ packet->chan3_scaled = chan3_scaled;
+ packet->chan4_scaled = chan4_scaled;
+ packet->chan5_scaled = chan5_scaled;
+ packet->chan6_scaled = chan6_scaled;
+ packet->chan7_scaled = chan7_scaled;
+ packet->chan8_scaled = chan8_scaled;
+ packet->port = port;
+ packet->rssi = rssi;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RC_CHANNELS_SCALED UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h
index c754ad8761..2ebcc54da5 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *msgbuf, 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)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, req_message_rate);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 4, req_stream_id);
+ _mav_put_uint8_t(buf, 5, start_stop);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
+#endif
+#else
+ mavlink_request_data_stream_t *packet = (mavlink_request_data_stream_t *)msgbuf;
+ packet->req_message_rate = req_message_rate;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->req_stream_id = req_stream_id;
+ packet->start_stop = start_stop;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE REQUEST_DATA_STREAM UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h
index ac3ef4fa9f..131b756b60 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(mavlink
#endif
}
+#if MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, roll_rate);
+ _mav_put_float(buf, 8, pitch_rate);
+ _mav_put_float(buf, 12, yaw_rate);
+ _mav_put_float(buf, 16, thrust);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN);
+#endif
+#else
+ mavlink_roll_pitch_yaw_rates_thrust_setpoint_t *packet = (mavlink_roll_pitch_yaw_rates_thrust_setpoint_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->roll_rate = roll_rate;
+ packet->pitch_rate = pitch_rate;
+ packet->yaw_rate = yaw_rate;
+ packet->thrust = thrust;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
index 626477322b..757e6d138b 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink
#endif
}
+#if MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, roll_speed);
+ _mav_put_float(buf, 8, pitch_speed);
+ _mav_put_float(buf, 12, yaw_speed);
+ _mav_put_float(buf, 16, thrust);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN);
+#endif
+#else
+ mavlink_roll_pitch_yaw_speed_thrust_setpoint_t *packet = (mavlink_roll_pitch_yaw_speed_thrust_setpoint_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->roll_speed = roll_speed;
+ packet->pitch_speed = pitch_speed;
+ packet->yaw_speed = yaw_speed;
+ packet->thrust = thrust;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
index ffcdc547b4..f04eedcb36 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_chann
#endif
}
+#if MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, roll);
+ _mav_put_float(buf, 8, pitch);
+ _mav_put_float(buf, 12, yaw);
+ _mav_put_float(buf, 16, thrust);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN);
+#endif
+#else
+ mavlink_roll_pitch_yaw_thrust_setpoint_t *packet = (mavlink_roll_pitch_yaw_thrust_setpoint_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->thrust = thrust;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
index fcd54cbb78..0176dfcc8d 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, p1x);
+ _mav_put_float(buf, 4, p1y);
+ _mav_put_float(buf, 8, p1z);
+ _mav_put_float(buf, 12, p2x);
+ _mav_put_float(buf, 16, p2y);
+ _mav_put_float(buf, 20, p2z);
+ _mav_put_uint8_t(buf, 24, frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
+#endif
+#else
+ mavlink_safety_allowed_area_t *packet = (mavlink_safety_allowed_area_t *)msgbuf;
+ packet->p1x = p1x;
+ packet->p1y = p1y;
+ packet->p1z = p1z;
+ packet->p2x = p2x;
+ packet->p2y = p2y;
+ packet->p2z = p2z;
+ packet->frame = frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SAFETY_ALLOWED_AREA UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h
index 61f6af1554..dafbc260b4 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h
@@ -234,6 +234,54 @@ static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t ch
#endif
}
+#if MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_safety_set_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, p1x);
+ _mav_put_float(buf, 4, p1y);
+ _mav_put_float(buf, 8, p1z);
+ _mav_put_float(buf, 12, p2x);
+ _mav_put_float(buf, 16, p2y);
+ _mav_put_float(buf, 20, p2z);
+ _mav_put_uint8_t(buf, 24, target_system);
+ _mav_put_uint8_t(buf, 25, target_component);
+ _mav_put_uint8_t(buf, 26, frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
+#endif
+#else
+ mavlink_safety_set_allowed_area_t *packet = (mavlink_safety_set_allowed_area_t *)msgbuf;
+ packet->p1x = p1x;
+ packet->p1y = p1y;
+ packet->p1z = p1z;
+ packet->p2x = p2x;
+ packet->p2y = p2y;
+ packet->p2z = p2z;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->frame = frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h
index 3010d051af..1648a56f89 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h
@@ -245,6 +245,56 @@ static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t
#endif
}
+#if MAVLINK_MSG_ID_SCALED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int16_t(buf, 4, xacc);
+ _mav_put_int16_t(buf, 6, yacc);
+ _mav_put_int16_t(buf, 8, zacc);
+ _mav_put_int16_t(buf, 10, xgyro);
+ _mav_put_int16_t(buf, 12, ygyro);
+ _mav_put_int16_t(buf, 14, zgyro);
+ _mav_put_int16_t(buf, 16, xmag);
+ _mav_put_int16_t(buf, 18, ymag);
+ _mav_put_int16_t(buf, 20, zmag);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN);
+#endif
+#else
+ mavlink_scaled_imu_t *packet = (mavlink_scaled_imu_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->xacc = xacc;
+ packet->yacc = yacc;
+ packet->zacc = zacc;
+ packet->xgyro = xgyro;
+ packet->ygyro = ygyro;
+ packet->zgyro = zgyro;
+ packet->xmag = xmag;
+ packet->ymag = ymag;
+ packet->zmag = zmag;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SCALED_IMU UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h
index ea4dbbf81d..1dea121dde 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h
@@ -245,6 +245,56 @@ static inline void mavlink_msg_scaled_imu2_send(mavlink_channel_t chan, uint32_t
#endif
}
+#if MAVLINK_MSG_ID_SCALED_IMU2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_scaled_imu2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int16_t(buf, 4, xacc);
+ _mav_put_int16_t(buf, 6, yacc);
+ _mav_put_int16_t(buf, 8, zacc);
+ _mav_put_int16_t(buf, 10, xgyro);
+ _mav_put_int16_t(buf, 12, ygyro);
+ _mav_put_int16_t(buf, 14, zgyro);
+ _mav_put_int16_t(buf, 16, xmag);
+ _mav_put_int16_t(buf, 18, ymag);
+ _mav_put_int16_t(buf, 20, zmag);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
+#endif
+#else
+ mavlink_scaled_imu2_t *packet = (mavlink_scaled_imu2_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->xacc = xacc;
+ packet->yacc = yacc;
+ packet->zacc = zacc;
+ packet->xgyro = xgyro;
+ packet->ygyro = ygyro;
+ packet->zgyro = zgyro;
+ packet->xmag = xmag;
+ packet->ymag = ymag;
+ packet->zmag = zmag;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SCALED_IMU2 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h
index 10324bc941..e0d6d87662 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_SCALED_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_scaled_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, press_abs);
+ _mav_put_float(buf, 8, press_diff);
+ _mav_put_int16_t(buf, 12, temperature);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
+#endif
+#else
+ mavlink_scaled_pressure_t *packet = (mavlink_scaled_pressure_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->press_abs = press_abs;
+ packet->press_diff = press_diff;
+ packet->temperature = temperature;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SCALED_PRESSURE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_serial_control.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_serial_control.h
new file mode 100644
index 0000000000..cbf72bae31
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_serial_control.h
@@ -0,0 +1,321 @@
+// MESSAGE SERIAL_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_SERIAL_CONTROL 126
+
+typedef struct __mavlink_serial_control_t
+{
+ uint32_t baudrate; ///< Baudrate of transfer. Zero means no change.
+ uint16_t timeout; ///< Timeout for reply data in milliseconds
+ uint8_t device; ///< See SERIAL_CONTROL_DEV enum
+ uint8_t flags; ///< See SERIAL_CONTROL_FLAG enum
+ uint8_t count; ///< how many bytes in this transfer
+ uint8_t data[70]; ///< serial data
+} mavlink_serial_control_t;
+
+#define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79
+#define MAVLINK_MSG_ID_126_LEN 79
+
+#define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220
+#define MAVLINK_MSG_ID_126_CRC 220
+
+#define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70
+
+#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \
+ "SERIAL_CONTROL", \
+ 6, \
+ { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \
+ { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \
+ { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a serial_control message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param device See SERIAL_CONTROL_DEV enum
+ * @param flags See SERIAL_CONTROL_FLAG enum
+ * @param timeout Timeout for reply data in milliseconds
+ * @param baudrate Baudrate of transfer. Zero means no change.
+ * @param count how many bytes in this transfer
+ * @param data serial data
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN];
+ _mav_put_uint32_t(buf, 0, baudrate);
+ _mav_put_uint16_t(buf, 4, timeout);
+ _mav_put_uint8_t(buf, 6, device);
+ _mav_put_uint8_t(buf, 7, flags);
+ _mav_put_uint8_t(buf, 8, count);
+ _mav_put_uint8_t_array(buf, 9, data, 70);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#else
+ mavlink_serial_control_t packet;
+ packet.baudrate = baudrate;
+ packet.timeout = timeout;
+ packet.device = device;
+ packet.flags = flags;
+ packet.count = count;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a serial_control message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param device See SERIAL_CONTROL_DEV enum
+ * @param flags See SERIAL_CONTROL_FLAG enum
+ * @param timeout Timeout for reply data in milliseconds
+ * @param baudrate Baudrate of transfer. Zero means no change.
+ * @param count how many bytes in this transfer
+ * @param data serial data
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t device,uint8_t flags,uint16_t timeout,uint32_t baudrate,uint8_t count,const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN];
+ _mav_put_uint32_t(buf, 0, baudrate);
+ _mav_put_uint16_t(buf, 4, timeout);
+ _mav_put_uint8_t(buf, 6, device);
+ _mav_put_uint8_t(buf, 7, flags);
+ _mav_put_uint8_t(buf, 8, count);
+ _mav_put_uint8_t_array(buf, 9, data, 70);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#else
+ mavlink_serial_control_t packet;
+ packet.baudrate = baudrate;
+ packet.timeout = timeout;
+ packet.device = device;
+ packet.flags = flags;
+ packet.count = count;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a serial_control struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control)
+{
+ return mavlink_msg_serial_control_pack(system_id, component_id, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data);
+}
+
+/**
+ * @brief Encode a serial_control struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control)
+{
+ return mavlink_msg_serial_control_pack_chan(system_id, component_id, chan, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data);
+}
+
+/**
+ * @brief Send a serial_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param device See SERIAL_CONTROL_DEV enum
+ * @param flags See SERIAL_CONTROL_FLAG enum
+ * @param timeout Timeout for reply data in milliseconds
+ * @param baudrate Baudrate of transfer. Zero means no change.
+ * @param count how many bytes in this transfer
+ * @param data serial data
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_serial_control_send(mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN];
+ _mav_put_uint32_t(buf, 0, baudrate);
+ _mav_put_uint16_t(buf, 4, timeout);
+ _mav_put_uint8_t(buf, 6, device);
+ _mav_put_uint8_t(buf, 7, flags);
+ _mav_put_uint8_t(buf, 8, count);
+ _mav_put_uint8_t_array(buf, 9, data, 70);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#endif
+#else
+ mavlink_serial_control_t packet;
+ packet.baudrate = baudrate;
+ packet.timeout = timeout;
+ packet.device = device;
+ packet.flags = flags;
+ packet.count = count;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, baudrate);
+ _mav_put_uint16_t(buf, 4, timeout);
+ _mav_put_uint8_t(buf, 6, device);
+ _mav_put_uint8_t(buf, 7, flags);
+ _mav_put_uint8_t(buf, 8, count);
+ _mav_put_uint8_t_array(buf, 9, data, 70);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#endif
+#else
+ mavlink_serial_control_t *packet = (mavlink_serial_control_t *)msgbuf;
+ packet->baudrate = baudrate;
+ packet->timeout = timeout;
+ packet->device = device;
+ packet->flags = flags;
+ packet->count = count;
+ mav_array_memcpy(packet->data, data, sizeof(uint8_t)*70);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SERIAL_CONTROL UNPACKING
+
+
+/**
+ * @brief Get field device from serial_control message
+ *
+ * @return See SERIAL_CONTROL_DEV enum
+ */
+static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field flags from serial_control message
+ *
+ * @return See SERIAL_CONTROL_FLAG enum
+ */
+static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field timeout from serial_control message
+ *
+ * @return Timeout for reply data in milliseconds
+ */
+static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field baudrate from serial_control message
+ *
+ * @return Baudrate of transfer. Zero means no change.
+ */
+static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field count from serial_control message
+ *
+ * @return how many bytes in this transfer
+ */
+static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field data from serial_control message
+ *
+ * @return serial data
+ */
+static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+ return _MAV_RETURN_uint8_t_array(msg, data, 70, 9);
+}
+
+/**
+ * @brief Decode a serial_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param serial_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_serial_control_decode(const mavlink_message_t* msg, mavlink_serial_control_t* serial_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ serial_control->baudrate = mavlink_msg_serial_control_get_baudrate(msg);
+ serial_control->timeout = mavlink_msg_serial_control_get_timeout(msg);
+ serial_control->device = mavlink_msg_serial_control_get_device(msg);
+ serial_control->flags = mavlink_msg_serial_control_get_flags(msg);
+ serial_control->count = mavlink_msg_serial_control_get_count(msg);
+ mavlink_msg_serial_control_get_data(msg, serial_control->data);
+#else
+ memcpy(serial_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
+#endif
+}
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h
index 6a14e93ed3..e8408862ff 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h
@@ -245,6 +245,56 @@ static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uin
#endif
}
+#if MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_servo_output_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_usec);
+ _mav_put_uint16_t(buf, 4, servo1_raw);
+ _mav_put_uint16_t(buf, 6, servo2_raw);
+ _mav_put_uint16_t(buf, 8, servo3_raw);
+ _mav_put_uint16_t(buf, 10, servo4_raw);
+ _mav_put_uint16_t(buf, 12, servo5_raw);
+ _mav_put_uint16_t(buf, 14, servo6_raw);
+ _mav_put_uint16_t(buf, 16, servo7_raw);
+ _mav_put_uint16_t(buf, 18, servo8_raw);
+ _mav_put_uint8_t(buf, 20, port);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
+#endif
+#else
+ mavlink_servo_output_raw_t *packet = (mavlink_servo_output_raw_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->servo1_raw = servo1_raw;
+ packet->servo2_raw = servo2_raw;
+ packet->servo3_raw = servo3_raw;
+ packet->servo4_raw = servo4_raw;
+ packet->servo5_raw = servo5_raw;
+ packet->servo6_raw = servo6_raw;
+ packet->servo7_raw = servo7_raw;
+ packet->servo8_raw = servo8_raw;
+ packet->port = port;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERVO_OUTPUT_RAW UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h
index 6f0d7a69da..94a7b432bf 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_set_global_position_setpoint_int_send(mavlink_cha
#endif
}
+#if MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_global_position_setpoint_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, latitude);
+ _mav_put_int32_t(buf, 4, longitude);
+ _mav_put_int32_t(buf, 8, altitude);
+ _mav_put_int16_t(buf, 12, yaw);
+ _mav_put_uint8_t(buf, 14, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN);
+#endif
+#else
+ mavlink_set_global_position_setpoint_int_t *packet = (mavlink_set_global_position_setpoint_int_t *)msgbuf;
+ packet->latitude = latitude;
+ packet->longitude = longitude;
+ packet->altitude = altitude;
+ packet->yaw = yaw;
+ packet->coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h
index c444d8d52c..1c018cbee3 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan
#endif
}
+#if MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, latitude);
+ _mav_put_int32_t(buf, 4, longitude);
+ _mav_put_int32_t(buf, 8, altitude);
+ _mav_put_uint8_t(buf, 12, target_system);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN);
+#endif
+#else
+ mavlink_set_gps_global_origin_t *packet = (mavlink_set_gps_global_origin_t *)msgbuf;
+ packet->latitude = latitude;
+ packet->longitude = longitude;
+ packet->altitude = altitude;
+ packet->target_system = target_system;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h
index 6f2835e031..04dbe6e9a2 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_set_local_position_setpoint_send(mavlink_channel_
#endif
}
+#if MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_local_position_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, x);
+ _mav_put_float(buf, 4, y);
+ _mav_put_float(buf, 8, z);
+ _mav_put_float(buf, 12, yaw);
+ _mav_put_uint8_t(buf, 16, target_system);
+ _mav_put_uint8_t(buf, 17, target_component);
+ _mav_put_uint8_t(buf, 18, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN);
+#endif
+#else
+ mavlink_set_local_position_setpoint_t *packet = (mavlink_set_local_position_setpoint_t *)msgbuf;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->yaw = yaw;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_LOCAL_POSITION_SETPOINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h
index 1aff42cce3..4b60a4120b 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t tar
#endif
}
+#if MAVLINK_MSG_ID_SET_MODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_mode_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, custom_mode);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, base_mode);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN);
+#endif
+#else
+ mavlink_set_mode_t *packet = (mavlink_set_mode_t *)msgbuf;
+ packet->custom_mode = custom_mode;
+ packet->target_system = target_system;
+ packet->base_mode = base_mode;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_MODE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h
index 8ceb8888fc..8c0e2a014a 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_set_quad_motors_setpoint_send(mavlink_channel_t c
#endif
}
+#if MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_quad_motors_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint16_t motor_front_nw, uint16_t motor_right_ne, uint16_t motor_back_se, uint16_t motor_left_sw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, motor_front_nw);
+ _mav_put_uint16_t(buf, 2, motor_right_ne);
+ _mav_put_uint16_t(buf, 4, motor_back_se);
+ _mav_put_uint16_t(buf, 6, motor_left_sw);
+ _mav_put_uint8_t(buf, 8, target_system);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN);
+#endif
+#else
+ mavlink_set_quad_motors_setpoint_t *packet = (mavlink_set_quad_motors_setpoint_t *)msgbuf;
+ packet->motor_front_nw = motor_front_nw;
+ packet->motor_right_ne = motor_right_ne;
+ packet->motor_back_se = motor_back_se;
+ packet->motor_left_sw = motor_left_sw;
+ packet->target_system = target_system;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_QUAD_MOTORS_SETPOINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h
index 9ef294cc97..c9a084773c 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h
@@ -234,6 +234,52 @@ static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_send(mav
#endif
}
+#if MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t group, uint8_t mode, const uint8_t *led_red, const uint8_t *led_blue, const uint8_t *led_green, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 32, group);
+ _mav_put_uint8_t(buf, 33, mode);
+ _mav_put_int16_t_array(buf, 0, roll, 4);
+ _mav_put_int16_t_array(buf, 8, pitch, 4);
+ _mav_put_int16_t_array(buf, 16, yaw, 4);
+ _mav_put_uint16_t_array(buf, 24, thrust, 4);
+ _mav_put_uint8_t_array(buf, 34, led_red, 4);
+ _mav_put_uint8_t_array(buf, 38, led_blue, 4);
+ _mav_put_uint8_t_array(buf, 42, led_green, 4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN);
+#endif
+#else
+ mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t *packet = (mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t *)msgbuf;
+ packet->group = group;
+ packet->mode = mode;
+ mav_array_memcpy(packet->roll, roll, sizeof(int16_t)*4);
+ mav_array_memcpy(packet->pitch, pitch, sizeof(int16_t)*4);
+ mav_array_memcpy(packet->yaw, yaw, sizeof(int16_t)*4);
+ mav_array_memcpy(packet->thrust, thrust, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet->led_red, led_red, sizeof(uint8_t)*4);
+ mav_array_memcpy(packet->led_blue, led_blue, sizeof(uint8_t)*4);
+ mav_array_memcpy(packet->led_green, led_green, sizeof(uint8_t)*4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h
index 7d8d526f8b..338bf0e438 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h
@@ -198,6 +198,46 @@ static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(mavlink
#endif
}
+#if MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t group, uint8_t mode, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 32, group);
+ _mav_put_uint8_t(buf, 33, mode);
+ _mav_put_int16_t_array(buf, 0, roll, 4);
+ _mav_put_int16_t_array(buf, 8, pitch, 4);
+ _mav_put_int16_t_array(buf, 16, yaw, 4);
+ _mav_put_uint16_t_array(buf, 24, thrust, 4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN);
+#endif
+#else
+ mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t *packet = (mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t *)msgbuf;
+ packet->group = group;
+ packet->mode = mode;
+ mav_array_memcpy(packet->roll, roll, sizeof(int16_t)*4);
+ mav_array_memcpy(packet->pitch, pitch, sizeof(int16_t)*4);
+ mav_array_memcpy(packet->yaw, yaw, sizeof(int16_t)*4);
+ mav_array_memcpy(packet->thrust, thrust, sizeof(uint16_t)*4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
index 5846ba41f7..4d0e5931fa 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_chan
#endif
}
+#if MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, roll_speed);
+ _mav_put_float(buf, 4, pitch_speed);
+ _mav_put_float(buf, 8, yaw_speed);
+ _mav_put_float(buf, 12, thrust);
+ _mav_put_uint8_t(buf, 16, target_system);
+ _mav_put_uint8_t(buf, 17, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN);
+#endif
+#else
+ mavlink_set_roll_pitch_yaw_speed_thrust_t *packet = (mavlink_set_roll_pitch_yaw_speed_thrust_t *)msgbuf;
+ packet->roll_speed = roll_speed;
+ packet->pitch_speed = pitch_speed;
+ packet->yaw_speed = yaw_speed;
+ packet->thrust = thrust;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
index 334fd39e36..21e0a43f24 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t
#endif
}
+#if MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, thrust);
+ _mav_put_uint8_t(buf, 16, target_system);
+ _mav_put_uint8_t(buf, 17, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN);
+#endif
+#else
+ mavlink_set_roll_pitch_yaw_thrust_t *packet = (mavlink_set_roll_pitch_yaw_thrust_t *)msgbuf;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->thrust = thrust;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_ROLL_PITCH_YAW_THRUST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h
index 93ce345b65..90b63427b9 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_setpoint_6dof_send(mavlink_channel_t chan, uint8_
#endif
}
+#if MAVLINK_MSG_ID_SETPOINT_6DOF_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_setpoint_6dof_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, trans_x);
+ _mav_put_float(buf, 4, trans_y);
+ _mav_put_float(buf, 8, trans_z);
+ _mav_put_float(buf, 12, rot_x);
+ _mav_put_float(buf, 16, rot_y);
+ _mav_put_float(buf, 20, rot_z);
+ _mav_put_uint8_t(buf, 24, target_system);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
+#endif
+#else
+ mavlink_setpoint_6dof_t *packet = (mavlink_setpoint_6dof_t *)msgbuf;
+ packet->trans_x = trans_x;
+ packet->trans_y = trans_y;
+ packet->trans_z = trans_z;
+ packet->rot_x = rot_x;
+ packet->rot_y = rot_y;
+ packet->rot_z = rot_z;
+ packet->target_system = target_system;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SETPOINT_6DOF UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h
index de80e46459..308a211cde 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h
@@ -234,6 +234,54 @@ static inline void mavlink_msg_setpoint_8dof_send(mavlink_channel_t chan, uint8_
#endif
}
+#if MAVLINK_MSG_ID_SETPOINT_8DOF_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_setpoint_8dof_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, val1);
+ _mav_put_float(buf, 4, val2);
+ _mav_put_float(buf, 8, val3);
+ _mav_put_float(buf, 12, val4);
+ _mav_put_float(buf, 16, val5);
+ _mav_put_float(buf, 20, val6);
+ _mav_put_float(buf, 24, val7);
+ _mav_put_float(buf, 28, val8);
+ _mav_put_uint8_t(buf, 32, target_system);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN);
+#endif
+#else
+ mavlink_setpoint_8dof_t *packet = (mavlink_setpoint_8dof_t *)msgbuf;
+ packet->val1 = val1;
+ packet->val2 = val2;
+ packet->val3 = val3;
+ packet->val4 = val4;
+ packet->val5 = val5;
+ packet->val6 = val6;
+ packet->val7 = val7;
+ packet->val8 = val8;
+ packet->target_system = target_system;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, (const char *)packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, (const char *)packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SETPOINT_8DOF UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h
index ebd657cf38..db3a926424 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h
@@ -366,6 +366,78 @@ static inline void mavlink_msg_sim_state_send(mavlink_channel_t chan, float q1,
#endif
}
+#if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, q1);
+ _mav_put_float(buf, 4, q2);
+ _mav_put_float(buf, 8, q3);
+ _mav_put_float(buf, 12, q4);
+ _mav_put_float(buf, 16, roll);
+ _mav_put_float(buf, 20, pitch);
+ _mav_put_float(buf, 24, yaw);
+ _mav_put_float(buf, 28, xacc);
+ _mav_put_float(buf, 32, yacc);
+ _mav_put_float(buf, 36, zacc);
+ _mav_put_float(buf, 40, xgyro);
+ _mav_put_float(buf, 44, ygyro);
+ _mav_put_float(buf, 48, zgyro);
+ _mav_put_float(buf, 52, lat);
+ _mav_put_float(buf, 56, lon);
+ _mav_put_float(buf, 60, alt);
+ _mav_put_float(buf, 64, std_dev_horz);
+ _mav_put_float(buf, 68, std_dev_vert);
+ _mav_put_float(buf, 72, vn);
+ _mav_put_float(buf, 76, ve);
+ _mav_put_float(buf, 80, vd);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN);
+#endif
+#else
+ mavlink_sim_state_t *packet = (mavlink_sim_state_t *)msgbuf;
+ packet->q1 = q1;
+ packet->q2 = q2;
+ packet->q3 = q3;
+ packet->q4 = q4;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->xacc = xacc;
+ packet->yacc = yacc;
+ packet->zacc = zacc;
+ packet->xgyro = xgyro;
+ packet->ygyro = ygyro;
+ packet->zgyro = zgyro;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt = alt;
+ packet->std_dev_horz = std_dev_horz;
+ packet->std_dev_vert = std_dev_vert;
+ packet->vn = vn;
+ packet->ve = ve;
+ packet->vd = vd;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SIM_STATE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h
index 2db627b96a..be2629dd8a 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h
@@ -234,6 +234,54 @@ static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, flo
#endif
}
+#if MAVLINK_MSG_ID_STATE_CORRECTION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_state_correction_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, xErr);
+ _mav_put_float(buf, 4, yErr);
+ _mav_put_float(buf, 8, zErr);
+ _mav_put_float(buf, 12, rollErr);
+ _mav_put_float(buf, 16, pitchErr);
+ _mav_put_float(buf, 20, yawErr);
+ _mav_put_float(buf, 24, vxErr);
+ _mav_put_float(buf, 28, vyErr);
+ _mav_put_float(buf, 32, vzErr);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN);
+#endif
+#else
+ mavlink_state_correction_t *packet = (mavlink_state_correction_t *)msgbuf;
+ packet->xErr = xErr;
+ packet->yErr = yErr;
+ packet->zErr = zErr;
+ packet->rollErr = rollErr;
+ packet->pitchErr = pitchErr;
+ packet->yawErr = yawErr;
+ packet->vxErr = vxErr;
+ packet->vyErr = vyErr;
+ packet->vzErr = vzErr;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE STATE_CORRECTION UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
index 536ca06349..c8c2547b31 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
@@ -151,6 +151,38 @@ static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t s
#endif
}
+#if MAVLINK_MSG_ID_STATUSTEXT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_statustext_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t severity, const char *text)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, severity);
+ _mav_put_char_array(buf, 1, text, 50);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN);
+#endif
+#else
+ mavlink_statustext_t *packet = (mavlink_statustext_t *)msgbuf;
+ packet->severity = severity;
+ mav_array_memcpy(packet->text, text, sizeof(char)*50);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)packet, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)packet, MAVLINK_MSG_ID_STATUSTEXT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE STATUSTEXT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h
index 101b366783..1b1730d5f5 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h
@@ -278,6 +278,62 @@ static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t
#endif
}
+#if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
+ _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
+ _mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
+ _mav_put_uint16_t(buf, 12, load);
+ _mav_put_uint16_t(buf, 14, voltage_battery);
+ _mav_put_int16_t(buf, 16, current_battery);
+ _mav_put_uint16_t(buf, 18, drop_rate_comm);
+ _mav_put_uint16_t(buf, 20, errors_comm);
+ _mav_put_uint16_t(buf, 22, errors_count1);
+ _mav_put_uint16_t(buf, 24, errors_count2);
+ _mav_put_uint16_t(buf, 26, errors_count3);
+ _mav_put_uint16_t(buf, 28, errors_count4);
+ _mav_put_int8_t(buf, 30, battery_remaining);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN);
+#endif
+#else
+ mavlink_sys_status_t *packet = (mavlink_sys_status_t *)msgbuf;
+ packet->onboard_control_sensors_present = onboard_control_sensors_present;
+ packet->onboard_control_sensors_enabled = onboard_control_sensors_enabled;
+ packet->onboard_control_sensors_health = onboard_control_sensors_health;
+ packet->load = load;
+ packet->voltage_battery = voltage_battery;
+ packet->current_battery = current_battery;
+ packet->drop_rate_comm = drop_rate_comm;
+ packet->errors_comm = errors_comm;
+ packet->errors_count1 = errors_count1;
+ packet->errors_count2 = errors_count2;
+ packet->errors_count3 = errors_count3;
+ packet->errors_count4 = errors_count4;
+ packet->battery_remaining = battery_remaining;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SYS_STATUS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h
index 1807567aea..988c669c36 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t
#endif
}
+#if MAVLINK_MSG_ID_SYSTEM_TIME_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_system_time_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_unix_usec);
+ _mav_put_uint32_t(buf, 8, time_boot_ms);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
+#endif
+#else
+ mavlink_system_time_t *packet = (mavlink_system_time_t *)msgbuf;
+ packet->time_unix_usec = time_unix_usec;
+ packet->time_boot_ms = time_boot_ms;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SYSTEM_TIME UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h
index 5b1093a3d7..b130ee50b5 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspe
#endif
}
+#if MAVLINK_MSG_ID_VFR_HUD_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_vfr_hud_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, airspeed);
+ _mav_put_float(buf, 4, groundspeed);
+ _mav_put_float(buf, 8, alt);
+ _mav_put_float(buf, 12, climb);
+ _mav_put_int16_t(buf, 16, heading);
+ _mav_put_uint16_t(buf, 18, throttle);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN);
+#endif
+#else
+ mavlink_vfr_hud_t *packet = (mavlink_vfr_hud_t *)msgbuf;
+ packet->airspeed = airspeed;
+ packet->groundspeed = groundspeed;
+ packet->alt = alt;
+ packet->climb = climb;
+ packet->heading = heading;
+ packet->throttle = throttle;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE VFR_HUD UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h
index a254202e4e..b3fa7bc1c1 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t ch
#endif
}
+#if MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_vicon_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, usec);
+ _mav_put_float(buf, 8, x);
+ _mav_put_float(buf, 12, y);
+ _mav_put_float(buf, 16, z);
+ _mav_put_float(buf, 20, roll);
+ _mav_put_float(buf, 24, pitch);
+ _mav_put_float(buf, 28, yaw);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN);
+#endif
+#else
+ mavlink_vicon_position_estimate_t *packet = (mavlink_vicon_position_estimate_t *)msgbuf;
+ packet->usec = usec;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE VICON_POSITION_ESTIMATE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h
index f7a741b09e..8f82fb6824 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t c
#endif
}
+#if MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, usec);
+ _mav_put_float(buf, 8, x);
+ _mav_put_float(buf, 12, y);
+ _mav_put_float(buf, 16, z);
+ _mav_put_float(buf, 20, roll);
+ _mav_put_float(buf, 24, pitch);
+ _mav_put_float(buf, 28, yaw);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
+#endif
+#else
+ mavlink_vision_position_estimate_t *packet = (mavlink_vision_position_estimate_t *)msgbuf;
+ packet->usec = usec;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE VISION_POSITION_ESTIMATE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h
index 6602251283..7528014c76 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan
#endif
}
+#if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, usec);
+ _mav_put_float(buf, 8, x);
+ _mav_put_float(buf, 12, y);
+ _mav_put_float(buf, 16, z);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
+#endif
+#else
+ mavlink_vision_speed_estimate_t *packet = (mavlink_vision_speed_estimate_t *)msgbuf;
+ packet->usec = usec;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE VISION_SPEED_ESTIMATE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/common/testsuite.h b/mavlink/include/mavlink/v1.0/common/testsuite.h
index c5aa9ddf3a..de23fcb2a2 100644
--- a/mavlink/include/mavlink/v1.0/common/testsuite.h
+++ b/mavlink/include/mavlink/v1.0/common/testsuite.h
@@ -2805,6 +2805,89 @@ static void mavlink_test_state_correction(uint8_t system_id, uint8_t component_i
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
+static void mavlink_test_rc_channels(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_rc_channels_t packet_in = {
+ 963497464,
+ }17443,
+ }17547,
+ }17651,
+ }17755,
+ }17859,
+ }17963,
+ }18067,
+ }18171,
+ }18275,
+ }18379,
+ }18483,
+ }18587,
+ }18691,
+ }18795,
+ }18899,
+ }19003,
+ }19107,
+ }19211,
+ }125,
+ }192,
+ };
+ mavlink_rc_channels_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.chan1_raw = packet_in.chan1_raw;
+ packet1.chan2_raw = packet_in.chan2_raw;
+ packet1.chan3_raw = packet_in.chan3_raw;
+ packet1.chan4_raw = packet_in.chan4_raw;
+ packet1.chan5_raw = packet_in.chan5_raw;
+ packet1.chan6_raw = packet_in.chan6_raw;
+ packet1.chan7_raw = packet_in.chan7_raw;
+ packet1.chan8_raw = packet_in.chan8_raw;
+ packet1.chan9_raw = packet_in.chan9_raw;
+ packet1.chan10_raw = packet_in.chan10_raw;
+ packet1.chan11_raw = packet_in.chan11_raw;
+ packet1.chan12_raw = packet_in.chan12_raw;
+ packet1.chan13_raw = packet_in.chan13_raw;
+ packet1.chan14_raw = packet_in.chan14_raw;
+ packet1.chan15_raw = packet_in.chan15_raw;
+ packet1.chan16_raw = packet_in.chan16_raw;
+ packet1.chan17_raw = packet_in.chan17_raw;
+ packet1.chan18_raw = packet_in.chan18_raw;
+ packet1.chancount = packet_in.chancount;
+ packet1.rssi = packet_in.rssi;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rc_channels_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_rc_channels_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rc_channels_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.chancount , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.chan13_raw , packet1.chan14_raw , packet1.chan15_raw , packet1.chan16_raw , packet1.chan17_raw , packet1.chan18_raw , packet1.rssi );
+ mavlink_msg_rc_channels_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rc_channels_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.chancount , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.chan13_raw , packet1.chan14_raw , packet1.chan15_raw , packet1.chan16_raw , packet1.chan17_raw , packet1.chan18_raw , packet1.rssi );
+ mavlink_msg_rc_channels_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
+ MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */
+ MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */
+ MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
+ MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */
+ MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
+ MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h
index bc47a547ad..c834a3df09 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_airspeeds_send(mavlink_channel_t chan, uint32_t t
#endif
}
+#if MAVLINK_MSG_ID_AIRSPEEDS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_airspeeds_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t airspeed_imu, int16_t airspeed_pitot, int16_t airspeed_hot_wire, int16_t airspeed_ultrasonic, int16_t aoa, int16_t aoy)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int16_t(buf, 4, airspeed_imu);
+ _mav_put_int16_t(buf, 6, airspeed_pitot);
+ _mav_put_int16_t(buf, 8, airspeed_hot_wire);
+ _mav_put_int16_t(buf, 10, airspeed_ultrasonic);
+ _mav_put_int16_t(buf, 12, aoa);
+ _mav_put_int16_t(buf, 14, aoy);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN);
+#endif
+#else
+ mavlink_airspeeds_t *packet = (mavlink_airspeeds_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->airspeed_imu = airspeed_imu;
+ packet->airspeed_pitot = airspeed_pitot;
+ packet->airspeed_hot_wire = airspeed_hot_wire;
+ packet->airspeed_ultrasonic = airspeed_ultrasonic;
+ packet->aoa = aoa;
+ packet->aoy = aoy;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, (const char *)packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, (const char *)packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE AIRSPEEDS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h
index e64787cc73..b009068ffc 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_altitudes_send(mavlink_channel_t chan, uint32_t t
#endif
}
+#if MAVLINK_MSG_ID_ALTITUDES_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_altitudes_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, alt_gps);
+ _mav_put_int32_t(buf, 8, alt_imu);
+ _mav_put_int32_t(buf, 12, alt_barometric);
+ _mav_put_int32_t(buf, 16, alt_optical_flow);
+ _mav_put_int32_t(buf, 20, alt_range_finder);
+ _mav_put_int32_t(buf, 24, alt_extra);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN);
+#endif
+#else
+ mavlink_altitudes_t *packet = (mavlink_altitudes_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->alt_gps = alt_gps;
+ packet->alt_imu = alt_imu;
+ packet->alt_barometric = alt_barometric;
+ packet->alt_optical_flow = alt_optical_flow;
+ packet->alt_range_finder = alt_range_finder;
+ packet->alt_extra = alt_extra;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)packet, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)packet, MAVLINK_MSG_ID_ALTITUDES_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE ALTITUDES UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h
index 581bd35dc5..e7b803a14b 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h
@@ -206,6 +206,48 @@ static inline void mavlink_msg_flexifunction_buffer_function_send(mavlink_channe
#endif
}
+#if MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_flexifunction_buffer_function_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t func_count, uint16_t data_address, uint16_t data_size, const int8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, func_index);
+ _mav_put_uint16_t(buf, 2, func_count);
+ _mav_put_uint16_t(buf, 4, data_address);
+ _mav_put_uint16_t(buf, 6, data_size);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_int8_t_array(buf, 10, data, 48);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN);
+#endif
+#else
+ mavlink_flexifunction_buffer_function_t *packet = (mavlink_flexifunction_buffer_function_t *)msgbuf;
+ packet->func_index = func_index;
+ packet->func_count = func_count;
+ packet->data_address = data_address;
+ packet->data_size = data_size;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ mav_array_memcpy(packet->data, data, sizeof(int8_t)*48);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FLEXIFUNCTION_BUFFER_FUNCTION UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h
index 790afd52b3..06631b40ed 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_flexifunction_buffer_function_ack_send(mavlink_ch
#endif
}
+#if MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_flexifunction_buffer_function_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, func_index);
+ _mav_put_uint16_t(buf, 2, result);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN);
+#endif
+#else
+ mavlink_flexifunction_buffer_function_ack_t *packet = (mavlink_flexifunction_buffer_function_ack_t *)msgbuf;
+ packet->func_index = func_index;
+ packet->result = result;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FLEXIFUNCTION_BUFFER_FUNCTION_ACK UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h
index ce722c8a4d..ac8366eefe 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h
@@ -168,6 +168,42 @@ static inline void mavlink_msg_flexifunction_command_send(mavlink_channel_t chan
#endif
}
+#if MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_flexifunction_command_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command_type)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, command_type);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
+#endif
+#else
+ mavlink_flexifunction_command_t *packet = (mavlink_flexifunction_command_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->command_type = command_type;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FLEXIFUNCTION_COMMAND UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h
index 070dc4bf8d..c88e2dc39f 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_flexifunction_command_ack_send(mavlink_channel_t
#endif
}
+#if MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_flexifunction_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command_type, uint16_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, command_type);
+ _mav_put_uint16_t(buf, 2, result);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN);
+#endif
+#else
+ mavlink_flexifunction_command_ack_t *packet = (mavlink_flexifunction_command_ack_t *)msgbuf;
+ packet->command_type = command_type;
+ packet->result = result;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FLEXIFUNCTION_COMMAND_ACK UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h
index ef262a6b1d..619f810c55 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h
@@ -195,6 +195,46 @@ static inline void mavlink_msg_flexifunction_directory_send(mavlink_channel_t ch
#endif
}
+#if MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_flexifunction_directory_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, const int8_t *directory_data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, directory_type);
+ _mav_put_uint8_t(buf, 3, start_index);
+ _mav_put_uint8_t(buf, 4, count);
+ _mav_put_int8_t_array(buf, 5, directory_data, 48);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN);
+#endif
+#else
+ mavlink_flexifunction_directory_t *packet = (mavlink_flexifunction_directory_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->directory_type = directory_type;
+ packet->start_index = start_index;
+ packet->count = count;
+ mav_array_memcpy(packet->directory_data, directory_data, sizeof(int8_t)*48);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FLEXIFUNCTION_DIRECTORY UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h
index d3a386ce54..0287183d85 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_flexifunction_directory_ack_send(mavlink_channel_
#endif
}
+#if MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_flexifunction_directory_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, uint16_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, result);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 4, directory_type);
+ _mav_put_uint8_t(buf, 5, start_index);
+ _mav_put_uint8_t(buf, 6, count);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN);
+#endif
+#else
+ mavlink_flexifunction_directory_ack_t *packet = (mavlink_flexifunction_directory_ack_t *)msgbuf;
+ packet->result = result;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->directory_type = directory_type;
+ packet->start_index = start_index;
+ packet->count = count;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FLEXIFUNCTION_DIRECTORY_ACK UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h
index e50f77b080..570782e792 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_flexifunction_read_req_send(mavlink_channel_t cha
#endif
}
+#if MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_flexifunction_read_req_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t read_req_type, int16_t data_index)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int16_t(buf, 0, read_req_type);
+ _mav_put_int16_t(buf, 2, data_index);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN);
+#endif
+#else
+ mavlink_flexifunction_read_req_t *packet = (mavlink_flexifunction_read_req_t *)msgbuf;
+ packet->read_req_type = read_req_type;
+ packet->data_index = data_index;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FLEXIFUNCTION_READ_REQ UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h
index 41afb3811d..c10000640d 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_flexifunction_set_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_flexifunction_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN);
+#endif
+#else
+ mavlink_flexifunction_set_t *packet = (mavlink_flexifunction_set_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FLEXIFUNCTION_SET UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h
index d21ab48168..bbb753a06b 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_serial_udb_extra_f13_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f13_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int16_t sue_week_no, int32_t sue_lat_origin, int32_t sue_lon_origin, int32_t sue_alt_origin)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, sue_lat_origin);
+ _mav_put_int32_t(buf, 4, sue_lon_origin);
+ _mav_put_int32_t(buf, 8, sue_alt_origin);
+ _mav_put_int16_t(buf, 12, sue_week_no);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f13_t *packet = (mavlink_serial_udb_extra_f13_t *)msgbuf;
+ packet->sue_lat_origin = sue_lat_origin;
+ packet->sue_lon_origin = sue_lon_origin;
+ packet->sue_alt_origin = sue_alt_origin;
+ packet->sue_week_no = sue_week_no;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F13 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h
index 6ac12f28a6..112564d006 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h
@@ -256,6 +256,58 @@ static inline void mavlink_msg_serial_udb_extra_f14_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f14_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t sue_WIND_ESTIMATION, uint8_t sue_GPS_TYPE, uint8_t sue_DR, uint8_t sue_BOARD_TYPE, uint8_t sue_AIRFRAME, int16_t sue_RCON, int16_t sue_TRAP_FLAGS, uint32_t sue_TRAP_SOURCE, int16_t sue_osc_fail_count, uint8_t sue_CLOCK_CONFIG, uint8_t sue_FLIGHT_PLAN_TYPE)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE);
+ _mav_put_int16_t(buf, 4, sue_RCON);
+ _mav_put_int16_t(buf, 6, sue_TRAP_FLAGS);
+ _mav_put_int16_t(buf, 8, sue_osc_fail_count);
+ _mav_put_uint8_t(buf, 10, sue_WIND_ESTIMATION);
+ _mav_put_uint8_t(buf, 11, sue_GPS_TYPE);
+ _mav_put_uint8_t(buf, 12, sue_DR);
+ _mav_put_uint8_t(buf, 13, sue_BOARD_TYPE);
+ _mav_put_uint8_t(buf, 14, sue_AIRFRAME);
+ _mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG);
+ _mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f14_t *packet = (mavlink_serial_udb_extra_f14_t *)msgbuf;
+ packet->sue_TRAP_SOURCE = sue_TRAP_SOURCE;
+ packet->sue_RCON = sue_RCON;
+ packet->sue_TRAP_FLAGS = sue_TRAP_FLAGS;
+ packet->sue_osc_fail_count = sue_osc_fail_count;
+ packet->sue_WIND_ESTIMATION = sue_WIND_ESTIMATION;
+ packet->sue_GPS_TYPE = sue_GPS_TYPE;
+ packet->sue_DR = sue_DR;
+ packet->sue_BOARD_TYPE = sue_BOARD_TYPE;
+ packet->sue_AIRFRAME = sue_AIRFRAME;
+ packet->sue_CLOCK_CONFIG = sue_CLOCK_CONFIG;
+ packet->sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F14 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h
index 10c3f4ca4f..77666407de 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h
@@ -158,6 +158,40 @@ static inline void mavlink_msg_serial_udb_extra_f15_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f15_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *sue_ID_VEHICLE_MODEL_NAME, const uint8_t *sue_ID_VEHICLE_REGISTRATION)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40);
+ _mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f15_t *packet = (mavlink_serial_udb_extra_f15_t *)msgbuf;
+
+ mav_array_memcpy(packet->sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40);
+ mav_array_memcpy(packet->sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F15 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h
index 659e6b7c52..ca9f0556f7 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h
@@ -158,6 +158,40 @@ static inline void mavlink_msg_serial_udb_extra_f16_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f16_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *sue_ID_LEAD_PILOT, const uint8_t *sue_ID_DIY_DRONES_URL)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40);
+ _mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f16_t *packet = (mavlink_serial_udb_extra_f16_t *)msgbuf;
+
+ mav_array_memcpy(packet->sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40);
+ mav_array_memcpy(packet->sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F16 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h
index 15ba68a346..41b9f09c00 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h
@@ -443,6 +443,92 @@ static inline void mavlink_msg_serial_udb_extra_f2_a_send(mavlink_channel_t chan
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f2_a_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t sue_time, uint8_t sue_status, int32_t sue_latitude, int32_t sue_longitude, int32_t sue_altitude, uint16_t sue_waypoint_index, int16_t sue_rmat0, int16_t sue_rmat1, int16_t sue_rmat2, int16_t sue_rmat3, int16_t sue_rmat4, int16_t sue_rmat5, int16_t sue_rmat6, int16_t sue_rmat7, int16_t sue_rmat8, uint16_t sue_cog, int16_t sue_sog, uint16_t sue_cpu_load, int16_t sue_voltage_milis, uint16_t sue_air_speed_3DIMU, int16_t sue_estimated_wind_0, int16_t sue_estimated_wind_1, int16_t sue_estimated_wind_2, int16_t sue_magFieldEarth0, int16_t sue_magFieldEarth1, int16_t sue_magFieldEarth2, int16_t sue_svs, int16_t sue_hdop)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, sue_time);
+ _mav_put_int32_t(buf, 4, sue_latitude);
+ _mav_put_int32_t(buf, 8, sue_longitude);
+ _mav_put_int32_t(buf, 12, sue_altitude);
+ _mav_put_uint16_t(buf, 16, sue_waypoint_index);
+ _mav_put_int16_t(buf, 18, sue_rmat0);
+ _mav_put_int16_t(buf, 20, sue_rmat1);
+ _mav_put_int16_t(buf, 22, sue_rmat2);
+ _mav_put_int16_t(buf, 24, sue_rmat3);
+ _mav_put_int16_t(buf, 26, sue_rmat4);
+ _mav_put_int16_t(buf, 28, sue_rmat5);
+ _mav_put_int16_t(buf, 30, sue_rmat6);
+ _mav_put_int16_t(buf, 32, sue_rmat7);
+ _mav_put_int16_t(buf, 34, sue_rmat8);
+ _mav_put_uint16_t(buf, 36, sue_cog);
+ _mav_put_int16_t(buf, 38, sue_sog);
+ _mav_put_uint16_t(buf, 40, sue_cpu_load);
+ _mav_put_int16_t(buf, 42, sue_voltage_milis);
+ _mav_put_uint16_t(buf, 44, sue_air_speed_3DIMU);
+ _mav_put_int16_t(buf, 46, sue_estimated_wind_0);
+ _mav_put_int16_t(buf, 48, sue_estimated_wind_1);
+ _mav_put_int16_t(buf, 50, sue_estimated_wind_2);
+ _mav_put_int16_t(buf, 52, sue_magFieldEarth0);
+ _mav_put_int16_t(buf, 54, sue_magFieldEarth1);
+ _mav_put_int16_t(buf, 56, sue_magFieldEarth2);
+ _mav_put_int16_t(buf, 58, sue_svs);
+ _mav_put_int16_t(buf, 60, sue_hdop);
+ _mav_put_uint8_t(buf, 62, sue_status);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f2_a_t *packet = (mavlink_serial_udb_extra_f2_a_t *)msgbuf;
+ packet->sue_time = sue_time;
+ packet->sue_latitude = sue_latitude;
+ packet->sue_longitude = sue_longitude;
+ packet->sue_altitude = sue_altitude;
+ packet->sue_waypoint_index = sue_waypoint_index;
+ packet->sue_rmat0 = sue_rmat0;
+ packet->sue_rmat1 = sue_rmat1;
+ packet->sue_rmat2 = sue_rmat2;
+ packet->sue_rmat3 = sue_rmat3;
+ packet->sue_rmat4 = sue_rmat4;
+ packet->sue_rmat5 = sue_rmat5;
+ packet->sue_rmat6 = sue_rmat6;
+ packet->sue_rmat7 = sue_rmat7;
+ packet->sue_rmat8 = sue_rmat8;
+ packet->sue_cog = sue_cog;
+ packet->sue_sog = sue_sog;
+ packet->sue_cpu_load = sue_cpu_load;
+ packet->sue_voltage_milis = sue_voltage_milis;
+ packet->sue_air_speed_3DIMU = sue_air_speed_3DIMU;
+ packet->sue_estimated_wind_0 = sue_estimated_wind_0;
+ packet->sue_estimated_wind_1 = sue_estimated_wind_1;
+ packet->sue_estimated_wind_2 = sue_estimated_wind_2;
+ packet->sue_magFieldEarth0 = sue_magFieldEarth0;
+ packet->sue_magFieldEarth1 = sue_magFieldEarth1;
+ packet->sue_magFieldEarth2 = sue_magFieldEarth2;
+ packet->sue_svs = sue_svs;
+ packet->sue_hdop = sue_hdop;
+ packet->sue_status = sue_status;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F2_A UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h
index 7cb8c87da5..3e1757f743 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h
@@ -498,6 +498,102 @@ static inline void mavlink_msg_serial_udb_extra_f2_b_send(mavlink_channel_t chan
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f2_b_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t sue_time, int16_t sue_pwm_input_1, int16_t sue_pwm_input_2, int16_t sue_pwm_input_3, int16_t sue_pwm_input_4, int16_t sue_pwm_input_5, int16_t sue_pwm_input_6, int16_t sue_pwm_input_7, int16_t sue_pwm_input_8, int16_t sue_pwm_input_9, int16_t sue_pwm_input_10, int16_t sue_pwm_output_1, int16_t sue_pwm_output_2, int16_t sue_pwm_output_3, int16_t sue_pwm_output_4, int16_t sue_pwm_output_5, int16_t sue_pwm_output_6, int16_t sue_pwm_output_7, int16_t sue_pwm_output_8, int16_t sue_pwm_output_9, int16_t sue_pwm_output_10, int16_t sue_imu_location_x, int16_t sue_imu_location_y, int16_t sue_imu_location_z, uint32_t sue_flags, int16_t sue_osc_fails, int16_t sue_imu_velocity_x, int16_t sue_imu_velocity_y, int16_t sue_imu_velocity_z, int16_t sue_waypoint_goal_x, int16_t sue_waypoint_goal_y, int16_t sue_waypoint_goal_z, int16_t sue_memory_stack_free)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, sue_time);
+ _mav_put_uint32_t(buf, 4, sue_flags);
+ _mav_put_int16_t(buf, 8, sue_pwm_input_1);
+ _mav_put_int16_t(buf, 10, sue_pwm_input_2);
+ _mav_put_int16_t(buf, 12, sue_pwm_input_3);
+ _mav_put_int16_t(buf, 14, sue_pwm_input_4);
+ _mav_put_int16_t(buf, 16, sue_pwm_input_5);
+ _mav_put_int16_t(buf, 18, sue_pwm_input_6);
+ _mav_put_int16_t(buf, 20, sue_pwm_input_7);
+ _mav_put_int16_t(buf, 22, sue_pwm_input_8);
+ _mav_put_int16_t(buf, 24, sue_pwm_input_9);
+ _mav_put_int16_t(buf, 26, sue_pwm_input_10);
+ _mav_put_int16_t(buf, 28, sue_pwm_output_1);
+ _mav_put_int16_t(buf, 30, sue_pwm_output_2);
+ _mav_put_int16_t(buf, 32, sue_pwm_output_3);
+ _mav_put_int16_t(buf, 34, sue_pwm_output_4);
+ _mav_put_int16_t(buf, 36, sue_pwm_output_5);
+ _mav_put_int16_t(buf, 38, sue_pwm_output_6);
+ _mav_put_int16_t(buf, 40, sue_pwm_output_7);
+ _mav_put_int16_t(buf, 42, sue_pwm_output_8);
+ _mav_put_int16_t(buf, 44, sue_pwm_output_9);
+ _mav_put_int16_t(buf, 46, sue_pwm_output_10);
+ _mav_put_int16_t(buf, 48, sue_imu_location_x);
+ _mav_put_int16_t(buf, 50, sue_imu_location_y);
+ _mav_put_int16_t(buf, 52, sue_imu_location_z);
+ _mav_put_int16_t(buf, 54, sue_osc_fails);
+ _mav_put_int16_t(buf, 56, sue_imu_velocity_x);
+ _mav_put_int16_t(buf, 58, sue_imu_velocity_y);
+ _mav_put_int16_t(buf, 60, sue_imu_velocity_z);
+ _mav_put_int16_t(buf, 62, sue_waypoint_goal_x);
+ _mav_put_int16_t(buf, 64, sue_waypoint_goal_y);
+ _mav_put_int16_t(buf, 66, sue_waypoint_goal_z);
+ _mav_put_int16_t(buf, 68, sue_memory_stack_free);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f2_b_t *packet = (mavlink_serial_udb_extra_f2_b_t *)msgbuf;
+ packet->sue_time = sue_time;
+ packet->sue_flags = sue_flags;
+ packet->sue_pwm_input_1 = sue_pwm_input_1;
+ packet->sue_pwm_input_2 = sue_pwm_input_2;
+ packet->sue_pwm_input_3 = sue_pwm_input_3;
+ packet->sue_pwm_input_4 = sue_pwm_input_4;
+ packet->sue_pwm_input_5 = sue_pwm_input_5;
+ packet->sue_pwm_input_6 = sue_pwm_input_6;
+ packet->sue_pwm_input_7 = sue_pwm_input_7;
+ packet->sue_pwm_input_8 = sue_pwm_input_8;
+ packet->sue_pwm_input_9 = sue_pwm_input_9;
+ packet->sue_pwm_input_10 = sue_pwm_input_10;
+ packet->sue_pwm_output_1 = sue_pwm_output_1;
+ packet->sue_pwm_output_2 = sue_pwm_output_2;
+ packet->sue_pwm_output_3 = sue_pwm_output_3;
+ packet->sue_pwm_output_4 = sue_pwm_output_4;
+ packet->sue_pwm_output_5 = sue_pwm_output_5;
+ packet->sue_pwm_output_6 = sue_pwm_output_6;
+ packet->sue_pwm_output_7 = sue_pwm_output_7;
+ packet->sue_pwm_output_8 = sue_pwm_output_8;
+ packet->sue_pwm_output_9 = sue_pwm_output_9;
+ packet->sue_pwm_output_10 = sue_pwm_output_10;
+ packet->sue_imu_location_x = sue_imu_location_x;
+ packet->sue_imu_location_y = sue_imu_location_y;
+ packet->sue_imu_location_z = sue_imu_location_z;
+ packet->sue_osc_fails = sue_osc_fails;
+ packet->sue_imu_velocity_x = sue_imu_velocity_x;
+ packet->sue_imu_velocity_y = sue_imu_velocity_y;
+ packet->sue_imu_velocity_z = sue_imu_velocity_z;
+ packet->sue_waypoint_goal_x = sue_waypoint_goal_x;
+ packet->sue_waypoint_goal_y = sue_waypoint_goal_y;
+ packet->sue_waypoint_goal_z = sue_waypoint_goal_z;
+ packet->sue_memory_stack_free = sue_memory_stack_free;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F2_B UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h
index 77c616cc2e..edd1e924c8 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h
@@ -245,6 +245,56 @@ static inline void mavlink_msg_serial_udb_extra_f4_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f4_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t sue_ROLL_STABILIZATION_AILERONS, uint8_t sue_ROLL_STABILIZATION_RUDDER, uint8_t sue_PITCH_STABILIZATION, uint8_t sue_YAW_STABILIZATION_RUDDER, uint8_t sue_YAW_STABILIZATION_AILERON, uint8_t sue_AILERON_NAVIGATION, uint8_t sue_RUDDER_NAVIGATION, uint8_t sue_ALTITUDEHOLD_STABILIZED, uint8_t sue_ALTITUDEHOLD_WAYPOINT, uint8_t sue_RACING_MODE)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS);
+ _mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER);
+ _mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION);
+ _mav_put_uint8_t(buf, 3, sue_YAW_STABILIZATION_RUDDER);
+ _mav_put_uint8_t(buf, 4, sue_YAW_STABILIZATION_AILERON);
+ _mav_put_uint8_t(buf, 5, sue_AILERON_NAVIGATION);
+ _mav_put_uint8_t(buf, 6, sue_RUDDER_NAVIGATION);
+ _mav_put_uint8_t(buf, 7, sue_ALTITUDEHOLD_STABILIZED);
+ _mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT);
+ _mav_put_uint8_t(buf, 9, sue_RACING_MODE);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f4_t *packet = (mavlink_serial_udb_extra_f4_t *)msgbuf;
+ packet->sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS;
+ packet->sue_ROLL_STABILIZATION_RUDDER = sue_ROLL_STABILIZATION_RUDDER;
+ packet->sue_PITCH_STABILIZATION = sue_PITCH_STABILIZATION;
+ packet->sue_YAW_STABILIZATION_RUDDER = sue_YAW_STABILIZATION_RUDDER;
+ packet->sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
+ packet->sue_AILERON_NAVIGATION = sue_AILERON_NAVIGATION;
+ packet->sue_RUDDER_NAVIGATION = sue_RUDDER_NAVIGATION;
+ packet->sue_ALTITUDEHOLD_STABILIZED = sue_ALTITUDEHOLD_STABILIZED;
+ packet->sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT;
+ packet->sue_RACING_MODE = sue_RACING_MODE;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F4 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h
index e115a9b445..a821f65bb7 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_serial_udb_extra_f5_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f5_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, sue_YAWKP_AILERON);
+ _mav_put_float(buf, 4, sue_YAWKD_AILERON);
+ _mav_put_float(buf, 8, sue_ROLLKP);
+ _mav_put_float(buf, 12, sue_ROLLKD);
+ _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON);
+ _mav_put_float(buf, 20, sue_AILERON_BOOST);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f5_t *packet = (mavlink_serial_udb_extra_f5_t *)msgbuf;
+ packet->sue_YAWKP_AILERON = sue_YAWKP_AILERON;
+ packet->sue_YAWKD_AILERON = sue_YAWKD_AILERON;
+ packet->sue_ROLLKP = sue_ROLLKP;
+ packet->sue_ROLLKD = sue_ROLLKD;
+ packet->sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
+ packet->sue_AILERON_BOOST = sue_AILERON_BOOST;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F5 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h
index 656103d090..0eb24c9866 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_serial_udb_extra_f6_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f6_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float sue_PITCHGAIN, float sue_PITCHKD, float sue_RUDDER_ELEV_MIX, float sue_ROLL_ELEV_MIX, float sue_ELEVATOR_BOOST)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, sue_PITCHGAIN);
+ _mav_put_float(buf, 4, sue_PITCHKD);
+ _mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX);
+ _mav_put_float(buf, 12, sue_ROLL_ELEV_MIX);
+ _mav_put_float(buf, 16, sue_ELEVATOR_BOOST);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f6_t *packet = (mavlink_serial_udb_extra_f6_t *)msgbuf;
+ packet->sue_PITCHGAIN = sue_PITCHGAIN;
+ packet->sue_PITCHKD = sue_PITCHKD;
+ packet->sue_RUDDER_ELEV_MIX = sue_RUDDER_ELEV_MIX;
+ packet->sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX;
+ packet->sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F6 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h
index 51c98e6b7a..58de7d01c8 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_serial_udb_extra_f7_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f7_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float sue_YAWKP_RUDDER, float sue_YAWKD_RUDDER, float sue_ROLLKP_RUDDER, float sue_ROLLKD_RUDDER, float sue_RUDDER_BOOST, float sue_RTL_PITCH_DOWN)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, sue_YAWKP_RUDDER);
+ _mav_put_float(buf, 4, sue_YAWKD_RUDDER);
+ _mav_put_float(buf, 8, sue_ROLLKP_RUDDER);
+ _mav_put_float(buf, 12, sue_ROLLKD_RUDDER);
+ _mav_put_float(buf, 16, sue_RUDDER_BOOST);
+ _mav_put_float(buf, 20, sue_RTL_PITCH_DOWN);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f7_t *packet = (mavlink_serial_udb_extra_f7_t *)msgbuf;
+ packet->sue_YAWKP_RUDDER = sue_YAWKP_RUDDER;
+ packet->sue_YAWKD_RUDDER = sue_YAWKD_RUDDER;
+ packet->sue_ROLLKP_RUDDER = sue_ROLLKP_RUDDER;
+ packet->sue_ROLLKD_RUDDER = sue_ROLLKD_RUDDER;
+ packet->sue_RUDDER_BOOST = sue_RUDDER_BOOST;
+ packet->sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F7 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h
index 8557a95e27..5cab816555 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_serial_udb_extra_f8_send(mavlink_channel_t chan,
#endif
}
+#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_serial_udb_extra_f8_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float sue_HEIGHT_TARGET_MAX, float sue_HEIGHT_TARGET_MIN, float sue_ALT_HOLD_THROTTLE_MIN, float sue_ALT_HOLD_THROTTLE_MAX, float sue_ALT_HOLD_PITCH_MIN, float sue_ALT_HOLD_PITCH_MAX, float sue_ALT_HOLD_PITCH_HIGH)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX);
+ _mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN);
+ _mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN);
+ _mav_put_float(buf, 12, sue_ALT_HOLD_THROTTLE_MAX);
+ _mav_put_float(buf, 16, sue_ALT_HOLD_PITCH_MIN);
+ _mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX);
+ _mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN);
+#endif
+#else
+ mavlink_serial_udb_extra_f8_t *packet = (mavlink_serial_udb_extra_f8_t *)msgbuf;
+ packet->sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX;
+ packet->sue_HEIGHT_TARGET_MIN = sue_HEIGHT_TARGET_MIN;
+ packet->sue_ALT_HOLD_THROTTLE_MIN = sue_ALT_HOLD_THROTTLE_MIN;
+ packet->sue_ALT_HOLD_THROTTLE_MAX = sue_ALT_HOLD_THROTTLE_MAX;
+ packet->sue_ALT_HOLD_PITCH_MIN = sue_ALT_HOLD_PITCH_MIN;
+ packet->sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX;
+ packet->sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SERIAL_UDB_EXTRA_F8 UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/version.h b/mavlink/include/mavlink/v1.0/matrixpilot/version.h
index a8be16c424..50cbda6c78 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/version.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Tue Feb 4 15:28:04 2014"
+#define MAVLINK_BUILD_DATE "Sun Apr 13 09:38:32 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h
index ef5354d5e1..f1cac9f2cd 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h
@@ -234,6 +234,54 @@ static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uin
#endif
}
+#if MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_attitude_control_send_buf(mavlink_message_t *msgbuf, 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)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, thrust);
+ _mav_put_uint8_t(buf, 16, target);
+ _mav_put_uint8_t(buf, 17, roll_manual);
+ _mav_put_uint8_t(buf, 18, pitch_manual);
+ _mav_put_uint8_t(buf, 19, yaw_manual);
+ _mav_put_uint8_t(buf, 20, thrust_manual);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN);
+#endif
+#else
+ mavlink_attitude_control_t *packet = (mavlink_attitude_control_t *)msgbuf;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->thrust = thrust;
+ packet->target = target;
+ packet->roll_manual = roll_manual;
+ packet->pitch_manual = pitch_manual;
+ packet->yaw_manual = yaw_manual;
+ packet->thrust_manual = thrust_manual;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE ATTITUDE_CONTROL UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h
index d41093792e..7bc27982a8 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h
@@ -217,6 +217,50 @@ static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float
#endif
}
+#if MAVLINK_MSG_ID_BRIEF_FEATURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_brief_feature_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t *descriptor, float response)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, x);
+ _mav_put_float(buf, 4, y);
+ _mav_put_float(buf, 8, z);
+ _mav_put_float(buf, 12, response);
+ _mav_put_uint16_t(buf, 16, size);
+ _mav_put_uint16_t(buf, 18, orientation);
+ _mav_put_uint8_t(buf, 20, orientation_assignment);
+ _mav_put_uint8_t_array(buf, 21, descriptor, 32);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN);
+#endif
+#else
+ mavlink_brief_feature_t *packet = (mavlink_brief_feature_t *)msgbuf;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->response = response;
+ packet->size = size;
+ packet->orientation = orientation;
+ packet->orientation_assignment = orientation_assignment;
+ mav_array_memcpy(packet->descriptor, descriptor, sizeof(uint8_t)*32);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE BRIEF_FEATURE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h
index ae4db825df..37270d49c0 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h
@@ -388,6 +388,82 @@ static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_image_available_send_buf(mavlink_message_t *msgbuf, 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, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, cam_id);
+ _mav_put_uint64_t(buf, 8, timestamp);
+ _mav_put_uint64_t(buf, 16, valid_until);
+ _mav_put_uint32_t(buf, 24, img_seq);
+ _mav_put_uint32_t(buf, 28, img_buf_index);
+ _mav_put_uint32_t(buf, 32, key);
+ _mav_put_uint32_t(buf, 36, exposure);
+ _mav_put_float(buf, 40, gain);
+ _mav_put_float(buf, 44, roll);
+ _mav_put_float(buf, 48, pitch);
+ _mav_put_float(buf, 52, yaw);
+ _mav_put_float(buf, 56, local_z);
+ _mav_put_float(buf, 60, lat);
+ _mav_put_float(buf, 64, lon);
+ _mav_put_float(buf, 68, alt);
+ _mav_put_float(buf, 72, ground_x);
+ _mav_put_float(buf, 76, ground_y);
+ _mav_put_float(buf, 80, ground_z);
+ _mav_put_uint16_t(buf, 84, width);
+ _mav_put_uint16_t(buf, 86, height);
+ _mav_put_uint16_t(buf, 88, depth);
+ _mav_put_uint8_t(buf, 90, cam_no);
+ _mav_put_uint8_t(buf, 91, channels);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN);
+#endif
+#else
+ mavlink_image_available_t *packet = (mavlink_image_available_t *)msgbuf;
+ packet->cam_id = cam_id;
+ packet->timestamp = timestamp;
+ packet->valid_until = valid_until;
+ packet->img_seq = img_seq;
+ packet->img_buf_index = img_buf_index;
+ packet->key = key;
+ packet->exposure = exposure;
+ packet->gain = gain;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->local_z = local_z;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt = alt;
+ packet->ground_x = ground_x;
+ packet->ground_y = ground_y;
+ packet->ground_z = ground_z;
+ packet->width = width;
+ packet->height = height;
+ packet->depth = depth;
+ packet->cam_no = cam_no;
+ packet->channels = channels;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE IMAGE_AVAILABLE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h
index 664574be94..85f8eff556 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h
@@ -146,6 +146,38 @@ static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan
#endif
}
+#if MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_image_trigger_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t enable)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, enable);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN);
+#endif
+#else
+ mavlink_image_trigger_control_t *packet = (mavlink_image_trigger_control_t *)msgbuf;
+ packet->enable = enable;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE IMAGE_TRIGGER_CONTROL UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h
index f3a2243afc..b438c74ea5 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h
@@ -267,6 +267,60 @@ static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_image_triggered_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, timestamp);
+ _mav_put_uint32_t(buf, 8, seq);
+ _mav_put_float(buf, 12, roll);
+ _mav_put_float(buf, 16, pitch);
+ _mav_put_float(buf, 20, yaw);
+ _mav_put_float(buf, 24, local_z);
+ _mav_put_float(buf, 28, lat);
+ _mav_put_float(buf, 32, lon);
+ _mav_put_float(buf, 36, alt);
+ _mav_put_float(buf, 40, ground_x);
+ _mav_put_float(buf, 44, ground_y);
+ _mav_put_float(buf, 48, ground_z);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN);
+#endif
+#else
+ mavlink_image_triggered_t *packet = (mavlink_image_triggered_t *)msgbuf;
+ packet->timestamp = timestamp;
+ packet->seq = seq;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->local_z = local_z;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt = alt;
+ packet->ground_x = ground_x;
+ packet->ground_y = ground_y;
+ packet->ground_z = ground_z;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE IMAGE_TRIGGERED UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h
index 6bdcceaf9a..05452637ea 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id,
#endif
}
+#if MAVLINK_MSG_ID_MARKER_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_marker_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, x);
+ _mav_put_float(buf, 4, y);
+ _mav_put_float(buf, 8, z);
+ _mav_put_float(buf, 12, roll);
+ _mav_put_float(buf, 16, pitch);
+ _mav_put_float(buf, 20, yaw);
+ _mav_put_uint16_t(buf, 24, id);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, MAVLINK_MSG_ID_MARKER_LEN);
+#endif
+#else
+ mavlink_marker_t *packet = (mavlink_marker_t *)msgbuf;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->id = id;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)packet, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)packet, MAVLINK_MSG_ID_MARKER_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE MARKER UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h
index aa7b827a36..bde400da9a 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h
@@ -173,6 +173,42 @@ static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uin
#endif
}
+#if MAVLINK_MSG_ID_PATTERN_DETECTED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_pattern_detected_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, float confidence, const char *file, uint8_t detected)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, confidence);
+ _mav_put_uint8_t(buf, 4, type);
+ _mav_put_uint8_t(buf, 105, detected);
+ _mav_put_char_array(buf, 5, file, 100);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN);
+#endif
+#else
+ mavlink_pattern_detected_t *packet = (mavlink_pattern_detected_t *)msgbuf;
+ packet->confidence = confidence;
+ packet->type = type;
+ packet->detected = detected;
+ mav_array_memcpy(packet->file, file, sizeof(char)*100);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE PATTERN_DETECTED UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h
index 913a52897e..86e9345194 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h
@@ -217,6 +217,50 @@ static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_point_of_interest_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char *name)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, x);
+ _mav_put_float(buf, 4, y);
+ _mav_put_float(buf, 8, z);
+ _mav_put_uint16_t(buf, 12, timeout);
+ _mav_put_uint8_t(buf, 14, type);
+ _mav_put_uint8_t(buf, 15, color);
+ _mav_put_uint8_t(buf, 16, coordinate_system);
+ _mav_put_char_array(buf, 17, name, 26);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN);
+#endif
+#else
+ mavlink_point_of_interest_t *packet = (mavlink_point_of_interest_t *)msgbuf;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->timeout = timeout;
+ packet->type = type;
+ packet->color = color;
+ packet->coordinate_system = coordinate_system;
+ mav_array_memcpy(packet->name, name, sizeof(char)*26);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE POINT_OF_INTEREST UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h
index e244364318..e5c04a851c 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h
@@ -250,6 +250,56 @@ static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel
#endif
}
+#if MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_point_of_interest_connection_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char *name)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, xp1);
+ _mav_put_float(buf, 4, yp1);
+ _mav_put_float(buf, 8, zp1);
+ _mav_put_float(buf, 12, xp2);
+ _mav_put_float(buf, 16, yp2);
+ _mav_put_float(buf, 20, zp2);
+ _mav_put_uint16_t(buf, 24, timeout);
+ _mav_put_uint8_t(buf, 26, type);
+ _mav_put_uint8_t(buf, 27, color);
+ _mav_put_uint8_t(buf, 28, coordinate_system);
+ _mav_put_char_array(buf, 29, name, 26);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN);
+#endif
+#else
+ mavlink_point_of_interest_connection_t *packet = (mavlink_point_of_interest_connection_t *)msgbuf;
+ packet->xp1 = xp1;
+ packet->yp1 = yp1;
+ packet->zp1 = zp1;
+ packet->xp2 = xp2;
+ packet->yp2 = yp2;
+ packet->zp2 = zp2;
+ packet->timeout = timeout;
+ packet->type = type;
+ packet->color = color;
+ packet->coordinate_system = coordinate_system;
+ mav_array_memcpy(packet->name, name, sizeof(char)*26);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE POINT_OF_INTEREST_CONNECTION UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h
index 6f4ca510ae..480004cefe 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h
@@ -190,6 +190,46 @@ static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t
#endif
}
+#if MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_position_control_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, x);
+ _mav_put_float(buf, 4, y);
+ _mav_put_float(buf, 8, z);
+ _mav_put_float(buf, 12, yaw);
+ _mav_put_uint16_t(buf, 16, id);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN);
+#endif
+#else
+ mavlink_position_control_setpoint_t *packet = (mavlink_position_control_setpoint_t *)msgbuf;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->yaw = yaw;
+ packet->id = id;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE POSITION_CONTROL_SETPOINT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h
index 08cedbb4b2..41a5126482 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h
@@ -212,6 +212,50 @@ static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc
#endif
}
+#if MAVLINK_MSG_ID_RAW_AUX_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_raw_aux_send_buf(mavlink_message_t *msgbuf, 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)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, baro);
+ _mav_put_uint16_t(buf, 4, adc1);
+ _mav_put_uint16_t(buf, 6, adc2);
+ _mav_put_uint16_t(buf, 8, adc3);
+ _mav_put_uint16_t(buf, 10, adc4);
+ _mav_put_uint16_t(buf, 12, vbat);
+ _mav_put_int16_t(buf, 14, temp);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN);
+#endif
+#else
+ mavlink_raw_aux_t *packet = (mavlink_raw_aux_t *)msgbuf;
+ packet->baro = baro;
+ packet->adc1 = adc1;
+ packet->adc2 = adc2;
+ packet->adc3 = adc3;
+ packet->adc4 = adc4;
+ packet->vbat = vbat;
+ packet->temp = temp;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)packet, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)packet, MAVLINK_MSG_ID_RAW_AUX_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE RAW_AUX UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h
index b26d748c25..8fe14dd546 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint
#endif
}
+#if MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_cam_shutter_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, gain);
+ _mav_put_uint16_t(buf, 4, interval);
+ _mav_put_uint16_t(buf, 6, exposure);
+ _mav_put_uint8_t(buf, 8, cam_no);
+ _mav_put_uint8_t(buf, 9, cam_mode);
+ _mav_put_uint8_t(buf, 10, trigger_pin);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN);
+#endif
+#else
+ mavlink_set_cam_shutter_t *packet = (mavlink_set_cam_shutter_t *)msgbuf;
+ packet->gain = gain;
+ packet->interval = interval;
+ packet->exposure = exposure;
+ packet->cam_no = cam_no;
+ packet->cam_mode = cam_mode;
+ packet->trigger_pin = trigger_pin;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_CAM_SHUTTER UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h
index f1f9e698f8..c4e4fc19a2 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_set_position_control_offset_send(mavlink_channel_
#endif
}
+#if MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_position_control_offset_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, x);
+ _mav_put_float(buf, 4, y);
+ _mav_put_float(buf, 8, z);
+ _mav_put_float(buf, 12, yaw);
+ _mav_put_uint8_t(buf, 16, target_system);
+ _mav_put_uint8_t(buf, 17, target_component);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN);
+#endif
+#else
+ mavlink_set_position_control_offset_t *packet = (mavlink_set_position_control_offset_t *)msgbuf;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->yaw = yaw;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SET_POSITION_CONTROL_OFFSET UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h
index 9458087da9..d71a2ed2e3 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h
@@ -179,6 +179,44 @@ static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uin
#endif
}
+#if MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_watchdog_command_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, watchdog_id);
+ _mav_put_uint16_t(buf, 2, process_id);
+ _mav_put_uint8_t(buf, 4, target_system_id);
+ _mav_put_uint8_t(buf, 5, command_id);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN);
+#endif
+#else
+ mavlink_watchdog_command_t *packet = (mavlink_watchdog_command_t *)msgbuf;
+ packet->watchdog_id = watchdog_id;
+ packet->process_id = process_id;
+ packet->target_system_id = target_system_id;
+ packet->command_id = command_id;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE WATCHDOG_COMMAND UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h
index 3f4295ee5d..a8e49b6426 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h
@@ -157,6 +157,40 @@ static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, u
#endif
}
+#if MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_watchdog_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, watchdog_id);
+ _mav_put_uint16_t(buf, 2, process_count);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN);
+#endif
+#else
+ mavlink_watchdog_heartbeat_t *packet = (mavlink_watchdog_heartbeat_t *)msgbuf;
+ packet->watchdog_id = watchdog_id;
+ packet->process_count = process_count;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE WATCHDOG_HEARTBEAT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h
index 55853cdde4..a5e0cc67e4 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h
@@ -185,6 +185,44 @@ static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan
#endif
}
+#if MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_watchdog_process_info_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const char *name, const char *arguments, int32_t timeout)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, timeout);
+ _mav_put_uint16_t(buf, 4, watchdog_id);
+ _mav_put_uint16_t(buf, 6, process_id);
+ _mav_put_char_array(buf, 8, name, 100);
+ _mav_put_char_array(buf, 108, arguments, 147);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN);
+#endif
+#else
+ mavlink_watchdog_process_info_t *packet = (mavlink_watchdog_process_info_t *)msgbuf;
+ packet->timeout = timeout;
+ packet->watchdog_id = watchdog_id;
+ packet->process_id = process_id;
+ mav_array_memcpy(packet->name, name, sizeof(char)*100);
+ mav_array_memcpy(packet->arguments, arguments, sizeof(char)*147);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE WATCHDOG_PROCESS_INFO UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h
index a0410d803e..15c9598e40 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h
@@ -201,6 +201,48 @@ static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t ch
#endif
}
+#if MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_watchdog_process_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, pid);
+ _mav_put_uint16_t(buf, 4, watchdog_id);
+ _mav_put_uint16_t(buf, 6, process_id);
+ _mav_put_uint16_t(buf, 8, crashes);
+ _mav_put_uint8_t(buf, 10, state);
+ _mav_put_uint8_t(buf, 11, muted);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN);
+#endif
+#else
+ mavlink_watchdog_process_status_t *packet = (mavlink_watchdog_process_status_t *)msgbuf;
+ packet->pid = pid;
+ packet->watchdog_id = watchdog_id;
+ packet->process_id = process_id;
+ packet->crashes = crashes;
+ packet->state = state;
+ packet->muted = muted;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE WATCHDOG_PROCESS_STATUS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h
index 428619eedb..a624a25797 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h
@@ -12,15 +12,15 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 0, 0, 0, 0, 0, 13, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 0, 0, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
+#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 0, 0, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 0, 0, 0, 0, 0, 29, 223, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 0, 0, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 0, 0, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
#include "../protocol.h"
@@ -56,6 +56,7 @@ enum MAV_CMD
MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
+ MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
@@ -73,8 +74,16 @@ enum MAV_CMD
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
+ MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */
+ MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */
+ MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
+ MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */
+ MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
+ MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/version.h b/mavlink/include/mavlink/v1.0/pixhawk/version.h
index aa79f6ffb5..6610a894c9 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/version.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Tue Feb 4 15:28:16 2014"
+#define MAVLINK_BUILD_DATE "Sun Apr 13 09:38:46 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h
index 73e9d75dbc..a87ce87d37 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h
@@ -173,6 +173,40 @@ static inline void mavlink_msg_cmd_airspeed_ack_send(mavlink_channel_t chan, flo
#endif
}
+#if MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_cmd_airspeed_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float spCmd, uint8_t ack)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, spCmd);
+ _mav_put_uint8_t(buf, 4, ack);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN);
+#endif
+#else
+ mavlink_cmd_airspeed_ack_t *packet = (mavlink_cmd_airspeed_ack_t *)msgbuf;
+ packet->spCmd = spCmd;
+ packet->ack = ack;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE CMD_AIRSPEED_ACK UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h
index b6b567f993..71d61e1e08 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h
@@ -173,6 +173,40 @@ static inline void mavlink_msg_cmd_airspeed_chng_send(mavlink_channel_t chan, ui
#endif
}
+#if MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_cmd_airspeed_chng_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target, float spCmd)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, spCmd);
+ _mav_put_uint8_t(buf, 4, target);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN);
+#endif
+#else
+ mavlink_cmd_airspeed_chng_t *packet = (mavlink_cmd_airspeed_chng_t *)msgbuf;
+ packet->spCmd = spCmd;
+ packet->target = target;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE CMD_AIRSPEED_CHNG UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h
index 642f7aab93..40a3db25a0 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h
@@ -154,6 +154,38 @@ static inline void mavlink_msg_filt_rot_vel_send(mavlink_channel_t chan, const f
#endif
}
+#if MAVLINK_MSG_ID_FILT_ROT_VEL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_filt_rot_vel_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const float *rotVel)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_float_array(buf, 0, rotVel, 3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN);
+#endif
+#else
+ mavlink_filt_rot_vel_t *packet = (mavlink_filt_rot_vel_t *)msgbuf;
+
+ mav_array_memcpy(packet->rotVel, rotVel, sizeof(float)*3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE FILT_ROT_VEL UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h
index 0f8369881a..bceed1013c 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h
@@ -174,6 +174,40 @@ static inline void mavlink_msg_llc_out_send(mavlink_channel_t chan, const int16_
#endif
}
+#if MAVLINK_MSG_ID_LLC_OUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_llc_out_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const int16_t *servoOut, const int16_t *MotorOut)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_int16_t_array(buf, 0, servoOut, 4);
+ _mav_put_int16_t_array(buf, 8, MotorOut, 2);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, MAVLINK_MSG_ID_LLC_OUT_LEN);
+#endif
+#else
+ mavlink_llc_out_t *packet = (mavlink_llc_out_t *)msgbuf;
+
+ mav_array_memcpy(packet->servoOut, servoOut, sizeof(int16_t)*4);
+ mav_array_memcpy(packet->MotorOut, MotorOut, sizeof(int16_t)*2);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)packet, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)packet, MAVLINK_MSG_ID_LLC_OUT_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE LLC_OUT UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h
index 5d93823262..f5a43e4fa4 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h
@@ -154,6 +154,38 @@ static inline void mavlink_msg_obs_air_temp_send(mavlink_channel_t chan, float a
#endif
}
+#if MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_obs_air_temp_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float airT)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, airT);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN);
+#endif
+#else
+ mavlink_obs_air_temp_t *packet = (mavlink_obs_air_temp_t *)msgbuf;
+ packet->airT = airT;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE OBS_AIR_TEMP UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h
index 35d813ca15..67d5ab2a22 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h
@@ -192,6 +192,42 @@ static inline void mavlink_msg_obs_air_velocity_send(mavlink_channel_t chan, flo
#endif
}
+#if MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_obs_air_velocity_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float magnitude, float aoa, float slip)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, magnitude);
+ _mav_put_float(buf, 4, aoa);
+ _mav_put_float(buf, 8, slip);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN);
+#endif
+#else
+ mavlink_obs_air_velocity_t *packet = (mavlink_obs_air_velocity_t *)msgbuf;
+ packet->magnitude = magnitude;
+ packet->aoa = aoa;
+ packet->slip = slip;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE OBS_AIR_VELOCITY UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h
index 9c80cd66eb..e1178e25fa 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h
@@ -154,6 +154,38 @@ static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const d
#endif
}
+#if MAVLINK_MSG_ID_OBS_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_obs_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const double *quat)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_double_array(buf, 0, quat, 4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN);
+#endif
+#else
+ mavlink_obs_attitude_t *packet = (mavlink_obs_attitude_t *)msgbuf;
+
+ mav_array_memcpy(packet->quat, quat, sizeof(double)*4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE OBS_ATTITUDE UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h
index 24dd43b579..b164687ff8 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h
@@ -174,6 +174,40 @@ static inline void mavlink_msg_obs_bias_send(mavlink_channel_t chan, const float
#endif
}
+#if MAVLINK_MSG_ID_OBS_BIAS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_obs_bias_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const float *accBias, const float *gyroBias)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_float_array(buf, 0, accBias, 3);
+ _mav_put_float_array(buf, 12, gyroBias, 3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, MAVLINK_MSG_ID_OBS_BIAS_LEN);
+#endif
+#else
+ mavlink_obs_bias_t *packet = (mavlink_obs_bias_t *)msgbuf;
+
+ mav_array_memcpy(packet->accBias, accBias, sizeof(float)*3);
+ mav_array_memcpy(packet->gyroBias, gyroBias, sizeof(float)*3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)packet, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)packet, MAVLINK_MSG_ID_OBS_BIAS_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE OBS_BIAS UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h
index cfc2fe7e10..f0ecef0e7e 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h
@@ -192,6 +192,42 @@ static inline void mavlink_msg_obs_position_send(mavlink_channel_t chan, int32_t
#endif
}
+#if MAVLINK_MSG_ID_OBS_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_obs_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lon, int32_t lat, int32_t alt)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, lon);
+ _mav_put_int32_t(buf, 4, lat);
+ _mav_put_int32_t(buf, 8, alt);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, MAVLINK_MSG_ID_OBS_POSITION_LEN);
+#endif
+#else
+ mavlink_obs_position_t *packet = (mavlink_obs_position_t *)msgbuf;
+ packet->lon = lon;
+ packet->lat = lat;
+ packet->alt = alt;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)packet, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)packet, MAVLINK_MSG_ID_OBS_POSITION_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE OBS_POSITION UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h
index 24e272bf7a..31617c8839 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h
@@ -154,6 +154,38 @@ static inline void mavlink_msg_obs_qff_send(mavlink_channel_t chan, float qff)
#endif
}
+#if MAVLINK_MSG_ID_OBS_QFF_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_obs_qff_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float qff)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, qff);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, MAVLINK_MSG_ID_OBS_QFF_LEN);
+#endif
+#else
+ mavlink_obs_qff_t *packet = (mavlink_obs_qff_t *)msgbuf;
+ packet->qff = qff;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)packet, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)packet, MAVLINK_MSG_ID_OBS_QFF_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE OBS_QFF UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h
index 6e3776632b..ec815d6929 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h
@@ -154,6 +154,38 @@ static inline void mavlink_msg_obs_velocity_send(mavlink_channel_t chan, const f
#endif
}
+#if MAVLINK_MSG_ID_OBS_VELOCITY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_obs_velocity_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const float *vel)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_float_array(buf, 0, vel, 3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN);
+#endif
+#else
+ mavlink_obs_velocity_t *packet = (mavlink_obs_velocity_t *)msgbuf;
+
+ mav_array_memcpy(packet->vel, vel, sizeof(float)*3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE OBS_VELOCITY UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h
index 55f7cb2ae1..c40391d441 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h
@@ -154,6 +154,38 @@ static inline void mavlink_msg_obs_wind_send(mavlink_channel_t chan, const float
#endif
}
+#if MAVLINK_MSG_ID_OBS_WIND_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_obs_wind_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const float *wind)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_float_array(buf, 0, wind, 3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, MAVLINK_MSG_ID_OBS_WIND_LEN);
+#endif
+#else
+ mavlink_obs_wind_t *packet = (mavlink_obs_wind_t *)msgbuf;
+
+ mav_array_memcpy(packet->wind, wind, sizeof(float)*3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)packet, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)packet, MAVLINK_MSG_ID_OBS_WIND_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE OBS_WIND UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h
index e0963ece79..70524f464c 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h
@@ -186,6 +186,40 @@ static inline void mavlink_msg_pm_elec_send(mavlink_channel_t chan, float PwCons
#endif
}
+#if MAVLINK_MSG_ID_PM_ELEC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_pm_elec_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float PwCons, float BatStat, const float *PwGen)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, PwCons);
+ _mav_put_float(buf, 4, BatStat);
+ _mav_put_float_array(buf, 8, PwGen, 3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, MAVLINK_MSG_ID_PM_ELEC_LEN);
+#endif
+#else
+ mavlink_pm_elec_t *packet = (mavlink_pm_elec_t *)msgbuf;
+ packet->PwCons = PwCons;
+ packet->BatStat = BatStat;
+ mav_array_memcpy(packet->PwGen, PwGen, sizeof(float)*3);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)packet, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)packet, MAVLINK_MSG_ID_PM_ELEC_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE PM_ELEC UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h
index 94f3e58bb9..72f8a8193b 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h
@@ -211,6 +211,44 @@ static inline void mavlink_msg_sys_stat_send(mavlink_channel_t chan, uint8_t gps
#endif
}
+#if MAVLINK_MSG_ID_SYS_Stat_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_sys_stat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, gps);
+ _mav_put_uint8_t(buf, 1, act);
+ _mav_put_uint8_t(buf, 2, mod);
+ _mav_put_uint8_t(buf, 3, commRssi);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, MAVLINK_MSG_ID_SYS_Stat_LEN);
+#endif
+#else
+ mavlink_sys_stat_t *packet = (mavlink_sys_stat_t *)msgbuf;
+ packet->gps = gps;
+ packet->act = act;
+ packet->mod = mod;
+ packet->commRssi = commRssi;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)packet, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)packet, MAVLINK_MSG_ID_SYS_Stat_LEN);
+#endif
+#endif
+}
+#endif
+
#endif
// MESSAGE SYS_Stat UNPACKING
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h b/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h
index 26666b0cc7..2eab863546 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h
@@ -12,15 +12,15 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 0, 0, 0, 0, 0, 13, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
+#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 0, 0, 0, 0, 0, 29, 223, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
#include "../protocol.h"
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/version.h b/mavlink/include/mavlink/v1.0/sensesoar/version.h
index cdd683949e..78d5628039 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/version.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Tue Feb 4 15:28:27 2014"
+#define MAVLINK_BUILD_DATE "Sun Apr 13 09:39:00 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
diff --git a/nuttx-configs/aerocore/include/board.h b/nuttx-configs/aerocore/include/board.h
new file mode 100644
index 0000000000..8705c1bc25
--- /dev/null
+++ b/nuttx-configs/aerocore/include/board.h
@@ -0,0 +1,263 @@
+/************************************************************************************
+ * configs/aerocore/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include
+#ifndef __ASSEMBLY__
+# include
+#endif
+
+#include
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Clocking *************************************************************************/
+/* The AeroCore uses a 24MHz crystal connected to the HSE.
+ *
+ * This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c:
+ * System Clock source : PLL (HSE)
+ * SYSCLK(Hz) : 168000000 Determined by PLL configuration
+ * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE)
+ * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE)
+ * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1)
+ * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2)
+ * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL)
+ * PLLM : 24 (STM32_PLLCFG_PLLM)
+ * PLLN : 336 (STM32_PLLCFG_PLLN)
+ * PLLP : 2 (STM32_PLLCFG_PLLP)
+ * PLLQ : 7 (STM32_PLLCFG_PPQ)
+ * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
+ * Flash Latency(WS) : 5
+ * Prefetch Buffer : OFF
+ * Instruction cache : ON
+ * Data cache : ON
+ * Require 48MHz for USB OTG FS, : Enabled
+ * SDIO and RNG clock
+ */
+
+/* HSI - 16 MHz RC factory-trimmed
+ * LSI - 32 KHz RC
+ * HSE - On-board crystal frequency is 24MHz
+ * LSE - not installed
+ */
+
+#define STM32_BOARD_XTAL 24000000ul
+
+#define STM32_HSI_FREQUENCY 16000000ul
+#define STM32_LSI_FREQUENCY 32000
+#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
+
+/* Main PLL Configuration.
+ *
+ * PLL source is HSE
+ * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
+ * = (24,000,000 / 24) * 336
+ * = 336,000,000
+ * SYSCLK = PLL_VCO / PLLP
+ * = 336,000,000 / 2 = 168,000,000
+ * USB OTG FS, SDIO and RNG Clock
+ * = PLL_VCO / PLLQ
+ * = 48,000,000
+ */
+
+#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
+#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
+#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
+#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7)
+
+#define STM32_SYSCLK_FREQUENCY 168000000ul
+
+/* AHB clock (HCLK) is SYSCLK (168MHz) */
+
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */
+
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
+
+/* Timers driven from APB1 will be twice PCLK1 */
+
+#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
+
+/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */
+
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
+#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
+
+/* Timers driven from APB2 will be twice PCLK2 */
+
+#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
+
+/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
+ * otherwise frequency is 2xAPBx.
+ * Note: TIM1,8 are on APB2, others on APB1
+ */
+
+#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
+#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
+
+/* Alternate function pin selections ************************************************/
+
+/*
+ * UARTs.
+ */
+/* USART1 on PB[6,7]: GPS */
+#define GPIO_USART1_RX GPIO_USART1_RX_2
+#define GPIO_USART1_TX GPIO_USART1_TX_2
+
+/* USART2 on PD[5,6]: J5 Breakout */
+#define GPIO_USART2_RX GPIO_USART2_RX_2
+#define GPIO_USART2_TX GPIO_USART2_TX_2
+#define GPIO_USART2_CTS 0 // unused
+#define GPIO_USART2_RTS 0 // unused
+
+/* USART3 on PD[8,9]: to DuoVero UART2 */
+#define GPIO_USART3_RX GPIO_USART3_RX_3
+#define GPIO_USART3_TX GPIO_USART3_TX_3
+#define GPIO_USART3_CTS 0 // unused
+#define GPIO_USART3_RTS 0 // unused
+
+/* UART7 on PE[78]: J7 Breakout */
+#define GPIO_UART7_RX GPIO_UART7_RX_1
+#define GPIO_UART7_TX GPIO_UART7_TX_1
+
+/*
+ * UART8 on PE[0-1]: System Console on Port C of USB (J7)
+ * No alternate pin config
+*/
+
+/* USART[1,6] require a RX DMA configuration */
+#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
+#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
+
+/*
+ * I2C
+ *
+ * The optional _GPIO configurations allow the I2C driver to manually
+ * reset the bus to clear stuck slaves. They match the pin configuration,
+ * but are normally-high GPIOs.
+ */
+
+/* PB[10-11]: I2C2 is broken out on J9 header */
+#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
+#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1
+#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
+
+/*
+ * SPI
+ */
+/* PA[4-7] SPI1 broken out on J12 */
+#define GPIO_SPI1_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) /* should be GPIO_SPI1_NSS_2 but use as a GPIO */
+#define GPIO_SPI1_SCK (GPIO_SPI1_SCK_1|GPIO_SPEED_50MHz)
+#define GPIO_SPI1_MISO (GPIO_SPI1_MISO_1|GPIO_SPEED_50MHz)
+#define GPIO_SPI1_MOSI (GPIO_SPI1_MOSI_1|GPIO_SPEED_50MHz)
+
+/* PB[12-15]: SPI2 connected to DuoVero SPI1 */
+#define GPIO_SPI2_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) /* should be GPIO_SPI2_NSS_2 but use as a GPIO */
+#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI2_MISO (GPIO_SPI2_MISO_1|GPIO_SPEED_50MHz)
+#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1|GPIO_SPEED_50MHz)
+
+/* PC[10-12]: SPI3 connected to onboard sensors */
+#define GPIO_SPI3_SCK (GPIO_SPI3_SCK_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI3_MISO (GPIO_SPI3_MISO_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI3_MOSI (GPIO_SPI3_MOSI_2|GPIO_SPEED_50MHz)
+
+/* PE[11-14]: SPI4 connected to FRAM */
+#define GPIO_SPI4_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN11) /* should be GPIO_SPI4_NSS_2 but use as a GPIO */
+#define GPIO_SPI4_SCK (GPIO_SPI4_SCK_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI4_MISO (GPIO_SPI4_MISO_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI4_MOSI (GPIO_SPI4_MOSI_2|GPIO_SPEED_50MHz)
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+EXTERN void stm32_boardinitialize(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/src/modules/controllib/uorb/UOrbPublication.cpp b/nuttx-configs/aerocore/include/nsh_romfsimg.h
similarity index 86%
rename from src/modules/controllib/uorb/UOrbPublication.cpp
rename to nuttx-configs/aerocore/include/nsh_romfsimg.h
index f69b39d90d..15e4e7a8d5 100644
--- a/src/modules/controllib/uorb/UOrbPublication.cpp
+++ b/nuttx-configs/aerocore/include/nsh_romfsimg.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,8 +32,11 @@
****************************************************************************/
/**
- * @file UOrbPublication.cpp
+ * nsh_romfsetc.h
*
+ * This file is a stub for 'make export' purposes; the actual ROMFS
+ * must be supplied by the library client.
*/
-#include "UOrbPublication.hpp"
+extern unsigned char romfs_img[];
+extern unsigned int romfs_img_len;
diff --git a/nuttx-configs/aerocore/nsh/Make.defs b/nuttx-configs/aerocore/nsh/Make.defs
new file mode 100644
index 0000000000..c7a1b71bbd
--- /dev/null
+++ b/nuttx-configs/aerocore/nsh/Make.defs
@@ -0,0 +1,179 @@
+############################################################################
+# configs/aerocore/nsh/Make.defs
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+include ${TOPDIR}/.config
+include ${TOPDIR}/tools/Config.mk
+
+#
+# We only support building with the ARM bare-metal toolchain from
+# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
+#
+CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
+
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+CC = $(CROSSDEV)gcc
+CXX = $(CROSSDEV)g++
+CPP = $(CROSSDEV)gcc -E
+LD = $(CROSSDEV)ld
+AR = $(CROSSDEV)ar rcs
+NM = $(CROSSDEV)nm
+OBJCOPY = $(CROSSDEV)objcopy
+OBJDUMP = $(CROSSDEV)objdump
+
+MAXOPTIMIZATION = -O3
+ARCHCPUFLAGS = -mcpu=cortex-m4 \
+ -mthumb \
+ -march=armv7e-m \
+ -mfpu=fpv4-sp-d16 \
+ -mfloat-abi=hard
+
+
+# enable precise stack overflow tracking
+INSTRUMENTATIONDEFINES = -finstrument-functions \
+ -ffixed-r10
+
+# pull in *just* libm from the toolchain ... this is grody
+LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
+EXTRA_LIBS += $(LIBM)
+
+# use our linker script
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
+else
+ ifeq ($(PX4_WINTOOL),y)
+ # Windows-native toolchains (MSYS)
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+ else
+ # Linux/Cygwin-native toolchain
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+ endif
+endif
+
+# tool versions
+ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
+ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
+
+# optimisation flags
+ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
+ -fno-strict-aliasing \
+ -fno-strength-reduce \
+ -fomit-frame-pointer \
+ -funsafe-math-optimizations \
+ -fno-builtin-printf \
+ -ffunction-sections \
+ -fdata-sections
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ARCHOPTIMIZATION += -g
+endif
+
+ARCHCFLAGS = -std=gnu99
+ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
+ARCHWARNINGS = -Wall \
+ -Wextra \
+ -Wdouble-promotion \
+ -Wshadow \
+ -Wfloat-equal \
+ -Wframe-larger-than=1024 \
+ -Wpointer-arith \
+ -Wlogical-op \
+ -Wmissing-declarations \
+ -Wpacked \
+ -Wno-unused-parameter
+# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
+# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
+# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
+
+ARCHCWARNINGS = $(ARCHWARNINGS) \
+ -Wbad-function-cast \
+ -Wstrict-prototypes \
+ -Wold-style-declaration \
+ -Wmissing-parameter-type \
+ -Wmissing-prototypes \
+ -Wnested-externs \
+ -Wunsuffixed-float-constants
+ARCHWARNINGSXX = $(ARCHWARNINGS) \
+ -Wno-psabi
+ARCHDEFINES =
+ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
+
+# this seems to be the only way to add linker flags
+EXTRA_LIBS += --warn-common \
+ --gc-sections
+
+CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
+CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
+CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
+CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+NXFLATLDFLAGS1 = -r -d -warn-common
+NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
+LDNXFLATFLAGS = -e main -s 2048
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+
+# produce partially-linked $1 from files in $2
+define PRELINK
+ @echo "PRELINK: $1"
+ $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
+endef
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
+
diff --git a/nuttx-configs/aerocore/nsh/appconfig b/nuttx-configs/aerocore/nsh/appconfig
new file mode 100644
index 0000000000..2850dac06e
--- /dev/null
+++ b/nuttx-configs/aerocore/nsh/appconfig
@@ -0,0 +1,42 @@
+############################################################################
+# configs/aerocore/nsh/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/nsh
+
+# The NSH application library
+CONFIGURED_APPS += nshlib
+CONFIGURED_APPS += system/readline
diff --git a/nuttx-configs/aerocore/nsh/defconfig b/nuttx-configs/aerocore/nsh/defconfig
new file mode 100644
index 0000000000..8d0bae7b9f
--- /dev/null
+++ b/nuttx-configs/aerocore/nsh/defconfig
@@ -0,0 +1,950 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+CONFIG_NUTTX_NEWCONFIG=y
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL is not set
+CONFIG_HOST_LINUX=y
+# CONFIG_HOST_OSX is not set
+# CONFIG_HOST_WINDOWS is not set
+# CONFIG_HOST_OTHER is not set
+
+#
+# Build Configuration
+#
+CONFIG_APPS_DIR="../apps"
+# CONFIG_BUILD_2PASS is not set
+
+#
+# Binary Output Formats
+#
+# CONFIG_RRLOAD_BINARY is not set
+# CONFIG_INTELHEX_BINARY is not set
+# CONFIG_MOTOROLA_SREC is not set
+CONFIG_RAW_BINARY=y
+
+#
+# Customize Header Files
+#
+# CONFIG_ARCH_STDBOOL_H is not set
+CONFIG_ARCH_MATH_H=y
+# CONFIG_ARCH_FLOAT_H is not set
+# CONFIG_ARCH_STDARG_H is not set
+
+#
+# Debug Options
+#
+# CONFIG_DEBUG is not set
+# CONFIG_DEBUG_SYMBOLS is not set
+
+#
+# System Type
+#
+# CONFIG_ARCH_8051 is not set
+CONFIG_ARCH_ARM=y
+# CONFIG_ARCH_AVR is not set
+# CONFIG_ARCH_HC is not set
+# CONFIG_ARCH_MIPS is not set
+# CONFIG_ARCH_RGMP is not set
+# CONFIG_ARCH_SH is not set
+# CONFIG_ARCH_SIM is not set
+# CONFIG_ARCH_X86 is not set
+# CONFIG_ARCH_Z16 is not set
+# CONFIG_ARCH_Z80 is not set
+CONFIG_ARCH="arm"
+
+#
+# ARM Options
+#
+# CONFIG_ARCH_CHIP_C5471 is not set
+# CONFIG_ARCH_CHIP_CALYPSO is not set
+# CONFIG_ARCH_CHIP_DM320 is not set
+# CONFIG_ARCH_CHIP_IMX is not set
+# CONFIG_ARCH_CHIP_KINETIS is not set
+# CONFIG_ARCH_CHIP_KL is not set
+# CONFIG_ARCH_CHIP_LM is not set
+# CONFIG_ARCH_CHIP_LPC17XX is not set
+# CONFIG_ARCH_CHIP_LPC214X is not set
+# CONFIG_ARCH_CHIP_LPC2378 is not set
+# CONFIG_ARCH_CHIP_LPC31XX is not set
+# CONFIG_ARCH_CHIP_LPC43XX is not set
+# CONFIG_ARCH_CHIP_NUC1XX is not set
+# CONFIG_ARCH_CHIP_SAM34 is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+CONFIG_ARCH_CORTEXM4=y
+CONFIG_ARCH_FAMILY="armv7-m"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_ARCH_HAVE_CMNVECTOR=y
+CONFIG_ARMV7M_CMNVECTOR=y
+CONFIG_ARCH_HAVE_FPU=y
+CONFIG_ARCH_FPU=y
+CONFIG_ARCH_HAVE_MPU=y
+# CONFIG_ARMV7M_MPU is not set
+
+#
+# ARMV7M Configuration Options
+#
+# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
+# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
+# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set
+CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y
+CONFIG_ARMV7M_STACKCHECK=y
+CONFIG_SERIAL_TERMIOS=y
+
+#
+# STM32 Configuration Options
+#
+# CONFIG_ARCH_CHIP_STM32L151C6 is not set
+# CONFIG_ARCH_CHIP_STM32L151C8 is not set
+# CONFIG_ARCH_CHIP_STM32L151CB is not set
+# CONFIG_ARCH_CHIP_STM32L151R6 is not set
+# CONFIG_ARCH_CHIP_STM32L151R8 is not set
+# CONFIG_ARCH_CHIP_STM32L151RB is not set
+# CONFIG_ARCH_CHIP_STM32L151V6 is not set
+# CONFIG_ARCH_CHIP_STM32L151V8 is not set
+# CONFIG_ARCH_CHIP_STM32L151VB is not set
+# CONFIG_ARCH_CHIP_STM32L152C6 is not set
+# CONFIG_ARCH_CHIP_STM32L152C8 is not set
+# CONFIG_ARCH_CHIP_STM32L152CB is not set
+# CONFIG_ARCH_CHIP_STM32L152R6 is not set
+# CONFIG_ARCH_CHIP_STM32L152R8 is not set
+# CONFIG_ARCH_CHIP_STM32L152RB is not set
+# CONFIG_ARCH_CHIP_STM32L152V6 is not set
+# CONFIG_ARCH_CHIP_STM32L152V8 is not set
+# CONFIG_ARCH_CHIP_STM32L152VB is not set
+# CONFIG_ARCH_CHIP_STM32F100C8 is not set
+# CONFIG_ARCH_CHIP_STM32F100CB is not set
+# CONFIG_ARCH_CHIP_STM32F100R8 is not set
+# CONFIG_ARCH_CHIP_STM32F100RB is not set
+# CONFIG_ARCH_CHIP_STM32F100RC is not set
+# CONFIG_ARCH_CHIP_STM32F100RD is not set
+# CONFIG_ARCH_CHIP_STM32F100RE is not set
+# CONFIG_ARCH_CHIP_STM32F100V8 is not set
+# CONFIG_ARCH_CHIP_STM32F100VB is not set
+# CONFIG_ARCH_CHIP_STM32F100VC is not set
+# CONFIG_ARCH_CHIP_STM32F100VD is not set
+# CONFIG_ARCH_CHIP_STM32F100VE is not set
+# CONFIG_ARCH_CHIP_STM32F103C4 is not set
+# CONFIG_ARCH_CHIP_STM32F103C8 is not set
+# CONFIG_ARCH_CHIP_STM32F103RET6 is not set
+# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
+# CONFIG_ARCH_CHIP_STM32F103VET6 is not set
+# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set
+# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set
+# CONFIG_ARCH_CHIP_STM32F107VC is not set
+# CONFIG_ARCH_CHIP_STM32F207IG is not set
+# CONFIG_ARCH_CHIP_STM32F302CB is not set
+# CONFIG_ARCH_CHIP_STM32F302CC is not set
+# CONFIG_ARCH_CHIP_STM32F302RB is not set
+# CONFIG_ARCH_CHIP_STM32F302RC is not set
+# CONFIG_ARCH_CHIP_STM32F302VB is not set
+# CONFIG_ARCH_CHIP_STM32F302VC is not set
+# CONFIG_ARCH_CHIP_STM32F303CB is not set
+# CONFIG_ARCH_CHIP_STM32F303CC is not set
+# CONFIG_ARCH_CHIP_STM32F303RB is not set
+# CONFIG_ARCH_CHIP_STM32F303RC is not set
+# CONFIG_ARCH_CHIP_STM32F303VB is not set
+# CONFIG_ARCH_CHIP_STM32F303VC is not set
+# CONFIG_ARCH_CHIP_STM32F405RG is not set
+# CONFIG_ARCH_CHIP_STM32F405VG is not set
+# CONFIG_ARCH_CHIP_STM32F405ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407VE is not set
+# CONFIG_ARCH_CHIP_STM32F407VG is not set
+# CONFIG_ARCH_CHIP_STM32F407ZE is not set
+# CONFIG_ARCH_CHIP_STM32F407ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407IE is not set
+# CONFIG_ARCH_CHIP_STM32F407IG is not set
+CONFIG_ARCH_CHIP_STM32F427V=y
+# CONFIG_ARCH_CHIP_STM32F427Z is not set
+# CONFIG_ARCH_CHIP_STM32F427I is not set
+# CONFIG_STM32_STM32L15XX is not set
+# CONFIG_STM32_ENERGYLITE is not set
+# CONFIG_STM32_STM32F10XX is not set
+# CONFIG_STM32_VALUELINE is not set
+# CONFIG_STM32_CONNECTIVITYLINE is not set
+# CONFIG_STM32_PERFORMANCELINE is not set
+# CONFIG_STM32_HIGHDENSITY is not set
+# CONFIG_STM32_MEDIUMDENSITY is not set
+# CONFIG_STM32_LOWDENSITY is not set
+# CONFIG_STM32_STM32F20XX is not set
+# CONFIG_STM32_STM32F30XX is not set
+CONFIG_STM32_STM32F40XX=y
+CONFIG_STM32_STM32F427=y
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+CONFIG_STM32_ADC1=y
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+CONFIG_STM32_BKPSRAM=y
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CAN2 is not set
+CONFIG_STM32_CCMDATARAM=y
+# CONFIG_STM32_CRC is not set
+# CONFIG_STM32_CRYP is not set
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=y
+# CONFIG_STM32_DAC1 is not set
+# CONFIG_STM32_DAC2 is not set
+# CONFIG_STM32_DCMI is not set
+# CONFIG_STM32_ETHMAC is not set
+# CONFIG_STM32_FSMC is not set
+# CONFIG_STM32_HASH is not set
+# CONFIG_STM32_I2C1 is not set
+CONFIG_STM32_I2C2=y
+# CONFIG_STM32_I2C3 is not set
+# CONFIG_STM32_OTGFS is not set
+# CONFIG_STM32_OTGHS is not set
+CONFIG_STM32_PWR=y
+# CONFIG_STM32_RNG is not set
+# CONFIG_STM32_SDIO is not set
+CONFIG_STM32_SPI1=y
+CONFIG_STM32_SPI2=y
+CONFIG_STM32_SPI3=y
+CONFIG_STM32_SPI4=y
+# CONFIG_STM32_SPI5 is not set
+# CONFIG_STM32_SPI6 is not set
+CONFIG_STM32_SYSCFG=y
+CONFIG_STM32_TIM1=y
+# CONFIG_STM32_TIM2 is not set
+CONFIG_STM32_TIM3=y
+CONFIG_STM32_TIM4=y
+CONFIG_STM32_TIM5=y
+# CONFIG_STM32_TIM6 is not set
+# CONFIG_STM32_TIM7 is not set
+# CONFIG_STM32_TIM8 is not set
+CONFIG_STM32_TIM9=y
+# CONFIG_STM32_TIM10 is not set
+# CONFIG_STM32_TIM11 is not set
+# CONFIG_STM32_TIM12 is not set
+# CONFIG_STM32_TIM13 is not set
+# CONFIG_STM32_TIM14 is not set
+CONFIG_STM32_USART1=y
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART3=y
+# CONFIG_STM32_UART4 is not set
+# CONFIG_STM32_UART5 is not set
+# CONFIG_STM32_USART6 is not set
+CONFIG_STM32_UART7=y
+CONFIG_STM32_UART8=y
+# CONFIG_STM32_IWDG is not set
+CONFIG_STM32_WWDG=y
+CONFIG_STM32_ADC=y
+CONFIG_STM32_SPI=y
+CONFIG_STM32_I2C=y
+
+#
+# Alternate Pin Mapping
+#
+CONFIG_STM32_FLASH_PREFETCH=y
+# CONFIG_STM32_JTAG_DISABLE is not set
+# CONFIG_STM32_JTAG_FULL_ENABLE is not set
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+# CONFIG_STM32_FORCEPOWER is not set
+# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
+# CONFIG_STM32_CCMEXCLUDE is not set
+CONFIG_STM32_DMACAPABLE=y
+# CONFIG_STM32_TIM1_PWM is not set
+# CONFIG_STM32_TIM3_PWM is not set
+# CONFIG_STM32_TIM4_PWM is not set
+# CONFIG_STM32_TIM5_PWM is not set
+# CONFIG_STM32_TIM9_PWM is not set
+# CONFIG_STM32_TIM1_ADC is not set
+# CONFIG_STM32_TIM3_ADC is not set
+# CONFIG_STM32_TIM4_ADC is not set
+# CONFIG_STM32_TIM5_ADC is not set
+CONFIG_STM32_USART=y
+
+#
+# U[S]ART Configuration
+#
+# CONFIG_USART1_RS485 is not set
+CONFIG_USART1_RXDMA=y
+# CONFIG_USART2_RS485 is not set
+CONFIG_USART2_RXDMA=y
+# CONFIG_USART3_RS485 is not set
+CONFIG_USART3_RXDMA=y
+# CONFIG_UART7_RS485 is not set
+CONFIG_UART7_RXDMA=y
+# CONFIG_UART8_RS485 is not set
+CONFIG_UART8_RXDMA=y
+CONFIG_SERIAL_DISABLE_REORDERING=y
+CONFIG_STM32_USART_SINGLEWIRE=y
+
+#
+# SPI Configuration
+#
+# CONFIG_STM32_SPI_INTERRUPTS is not set
+# CONFIG_STM32_SPI_DMA is not set
+
+#
+# I2C Configuration
+#
+# CONFIG_STM32_I2C_DYNTIMEO is not set
+CONFIG_STM32_I2CTIMEOSEC=0
+CONFIG_STM32_I2CTIMEOMS=10
+CONFIG_STM32_I2CTIMEOTICKS=500
+# CONFIG_STM32_I2C_DUTY16_9 is not set
+
+#
+# USB Host Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# External Memory Configuration
+#
+
+#
+# Architecture Options
+#
+# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_VECNOTIRQ is not set
+CONFIG_ARCH_DMA=y
+CONFIG_ARCH_IRQPRIO=y
+# CONFIG_CUSTOM_STACK is not set
+# CONFIG_ADDRENV is not set
+CONFIG_ARCH_HAVE_VFORK=y
+CONFIG_ARCH_STACKDUMP=y
+# CONFIG_ENDIAN_BIG is not set
+# CONFIG_ARCH_HAVE_RAMFUNCS is not set
+CONFIG_ARCH_HAVE_RAMVECTORS=y
+# CONFIG_ARCH_RAMVECTORS is not set
+
+#
+# Board Settings
+#
+CONFIG_BOARD_LOOPSPERMSEC=16717
+# CONFIG_ARCH_CALIBRATION is not set
+CONFIG_DRAM_START=0x20000000
+CONFIG_DRAM_SIZE=262144
+CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
+CONFIG_ARCH_INTERRUPTSTACK=4096
+
+#
+# Boot options
+#
+# CONFIG_BOOT_RUNFROMEXTSRAM is not set
+CONFIG_BOOT_RUNFROMFLASH=y
+# CONFIG_BOOT_RUNFROMISRAM is not set
+# CONFIG_BOOT_RUNFROMSDRAM is not set
+# CONFIG_BOOT_COPYTORAM is not set
+
+#
+# Board Selection
+#
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD=""
+
+#
+# Common Board Options
+#
+CONFIG_NSH_MMCSDMINOR=0
+
+#
+# Board-Specific Options
+#
+
+#
+# RTOS Features
+#
+# CONFIG_BOARD_INITIALIZE is not set
+CONFIG_MSEC_PER_TICK=1
+CONFIG_RR_INTERVAL=0
+CONFIG_SCHED_INSTRUMENTATION=y
+CONFIG_TASK_NAME_SIZE=24
+# CONFIG_SCHED_HAVE_PARENT is not set
+# CONFIG_JULIAN_TIME is not set
+CONFIG_START_YEAR=1970
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=1
+CONFIG_DEV_CONSOLE=y
+# CONFIG_MUTEX_TYPES is not set
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_SEM_PREALLOCHOLDERS=0
+CONFIG_SEM_NNESTPRIO=8
+# CONFIG_FDCLONE_DISABLE is not set
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SCHED_WAITPID=y
+# CONFIG_SCHED_STARTHOOK is not set
+CONFIG_SCHED_ATEXIT=y
+CONFIG_SCHED_ATEXIT_MAX=1
+# CONFIG_SCHED_ONEXIT is not set
+CONFIG_USER_ENTRYPOINT="nsh_main"
+# CONFIG_DISABLE_OS_API is not set
+
+#
+# Signal Numbers
+#
+CONFIG_SIG_SIGUSR1=1
+CONFIG_SIG_SIGUSR2=2
+CONFIG_SIG_SIGALARM=3
+CONFIG_SIG_SIGCONDTIMEDOUT=16
+CONFIG_SIG_SIGWORK=4
+
+#
+# Sizes of configurable things (0 disables)
+#
+CONFIG_MAX_TASKS=32
+CONFIG_MAX_TASK_ARGS=10
+CONFIG_NPTHREAD_KEYS=4
+CONFIG_NFILE_DESCRIPTORS=36
+CONFIG_NFILE_STREAMS=8
+CONFIG_NAME_MAX=32
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=50
+CONFIG_PREALLOC_TIMERS=50
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=6000
+CONFIG_USERMAIN_STACKSIZE=4096
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_PTHREAD_STACK_DEFAULT=2048
+
+#
+# Device Drivers
+#
+# CONFIG_DISABLE_POLL is not set
+CONFIG_DEV_NULL=y
+# CONFIG_DEV_ZERO is not set
+# CONFIG_LOOP is not set
+# CONFIG_RAMDISK is not set
+# CONFIG_CAN is not set
+# CONFIG_PWM is not set
+CONFIG_I2C=y
+# CONFIG_I2C_SLAVE is not set
+CONFIG_I2C_TRANSFER=y
+# CONFIG_I2C_WRITEREAD is not set
+# CONFIG_I2C_POLLED is not set
+# CONFIG_I2C_TRACE is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+CONFIG_I2C_RESET=y
+CONFIG_SPI=y
+# CONFIG_SPI_OWNBUS is not set
+CONFIG_SPI_EXCHANGE=y
+# CONFIG_SPI_CMDDATA is not set
+# CONFIG_RTC is not set
+CONFIG_WATCHDOG=y
+# CONFIG_ANALOG is not set
+# CONFIG_AUDIO_DEVICES is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+# CONFIG_LCD is not set
+# CONFIG_MMCSD is not set
+CONFIG_MTD=y
+
+#
+# MTD Configuration
+#
+CONFIG_MTD_PARTITION=y
+CONFIG_MTD_BYTE_WRITE=y
+
+#
+# MTD Device Drivers
+#
+# CONFIG_RAMMTD is not set
+# CONFIG_MTD_AT24XX is not set
+# CONFIG_MTD_AT45DB is not set
+# CONFIG_MTD_M25P is not set
+# CONFIG_MTD_SMART is not set
+CONFIG_MTD_RAMTRON=y
+CONFIG_RAMTRON_FUJITSU=y
+# CONFIG_MTD_SST25 is not set
+# CONFIG_MTD_SST39FV is not set
+# CONFIG_MTD_W25 is not set
+CONFIG_PIPES=y
+# CONFIG_PM is not set
+# CONFIG_POWER is not set
+# CONFIG_SENSORS is not set
+CONFIG_SERIAL=y
+# CONFIG_DEV_LOWCONSOLE is not set
+# CONFIG_16550_UART is not set
+CONFIG_ARCH_HAVE_UART7=y
+CONFIG_ARCH_HAVE_UART8=y
+CONFIG_ARCH_HAVE_USART1=y
+CONFIG_ARCH_HAVE_USART2=y
+CONFIG_ARCH_HAVE_USART3=y
+CONFIG_MCU_SERIAL=y
+CONFIG_STANDARD_SERIAL=y
+CONFIG_SERIAL_NPOLLWAITERS=2
+# CONFIG_USART1_SERIAL_CONSOLE is not set
+# CONFIG_USART2_SERIAL_CONSOLE is not set
+# CONFIG_USART3_SERIAL_CONSOLE is not set
+# CONFIG_UART7_SERIAL_CONSOLE is not set
+CONFIG_UART8_SERIAL_CONSOLE=y
+# CONFIG_NO_SERIAL_CONSOLE is not set
+
+#
+# USART1 Configuration
+#
+CONFIG_USART1_RXBUFSIZE=512
+CONFIG_USART1_TXBUFSIZE=512
+CONFIG_USART1_BAUD=115200
+CONFIG_USART1_BITS=8
+CONFIG_USART1_PARITY=0
+CONFIG_USART1_2STOP=0
+# CONFIG_USART1_IFLOWCONTROL is not set
+# CONFIG_USART1_OFLOWCONTROL is not set
+
+#
+# USART2 Configuration
+#
+CONFIG_USART2_RXBUFSIZE=512
+CONFIG_USART2_TXBUFSIZE=512
+CONFIG_USART2_BAUD=115200
+CONFIG_USART2_BITS=8
+CONFIG_USART2_PARITY=0
+CONFIG_USART2_2STOP=0
+# CONFIG_USART2_IFLOWCONTROL is not set
+# CONFIG_USART2_OFLOWCONTROL is not set
+
+#
+# USART3 Configuration
+#
+CONFIG_USART3_RXBUFSIZE=512
+CONFIG_USART3_TXBUFSIZE=512
+CONFIG_USART3_BAUD=115200
+CONFIG_USART3_BITS=8
+CONFIG_USART3_PARITY=0
+CONFIG_USART3_2STOP=0
+# CONFIG_USART3_IFLOWCONTROL is not set
+# CONFIG_USART3_OFLOWCONTROL is not set
+
+#
+# UART7 Configuration
+#
+CONFIG_UART7_RXBUFSIZE=512
+CONFIG_UART7_TXBUFSIZE=512
+CONFIG_UART7_BAUD=115200
+CONFIG_UART7_BITS=8
+CONFIG_UART7_PARITY=0
+CONFIG_UART7_2STOP=0
+# CONFIG_UART7_IFLOWCONTROL is not set
+# CONFIG_UART7_OFLOWCONTROL is not set
+
+#
+# UART8 Configuration
+#
+CONFIG_UART8_RXBUFSIZE=512
+CONFIG_UART8_TXBUFSIZE=512
+CONFIG_UART8_BAUD=115200
+CONFIG_UART8_BITS=8
+CONFIG_UART8_PARITY=0
+CONFIG_UART8_2STOP=0
+# CONFIG_UART8_IFLOWCONTROL is not set
+# CONFIG_UART8_OFLOWCONTROL is not set
+# CONFIG_SERIAL_IFLOWCONTROL is not set
+# CONFIG_SERIAL_OFLOWCONTROL is not set
+# CONFIG_USBDEV is not set
+# CONFIG_USBHOST is not set
+# CONFIG_WIRELESS is not set
+
+#
+# System Logging Device Options
+#
+
+#
+# System Logging
+#
+# CONFIG_RAMLOG is not set
+
+#
+# Networking Support
+#
+# CONFIG_NET is not set
+
+#
+# File Systems
+#
+
+#
+# File system configuration
+#
+# CONFIG_DISABLE_MOUNTPOINT is not set
+# CONFIG_FS_RAMMAP is not set
+CONFIG_FS_FAT=y
+CONFIG_FAT_LCNAMES=y
+CONFIG_FAT_LFN=y
+CONFIG_FAT_MAXFNAME=32
+CONFIG_FS_FATTIME=y
+CONFIG_FAT_DMAMEMORY=y
+CONFIG_FS_NXFFS=y
+CONFIG_NXFFS_PREALLOCATED=y
+CONFIG_NXFFS_ERASEDSTATE=0xff
+CONFIG_NXFFS_PACKTHRESHOLD=32
+CONFIG_NXFFS_MAXNAMLEN=32
+CONFIG_NXFFS_TAILTHRESHOLD=2048
+CONFIG_FS_ROMFS=y
+# CONFIG_FS_SMARTFS is not set
+CONFIG_FS_BINFS=y
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG_ENABLE is not set
+# CONFIG_SYSLOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_NX is not set
+
+#
+# Memory Management
+#
+# CONFIG_MM_MULTIHEAP is not set
+# CONFIG_MM_SMALL is not set
+CONFIG_MM_REGIONS=2
+CONFIG_GRAN=y
+# CONFIG_GRAN_SINGLE is not set
+# CONFIG_GRAN_INTR is not set
+
+#
+# Audio Support
+#
+# CONFIG_AUDIO is not set
+
+#
+# Binary Formats
+#
+# CONFIG_BINFMT_DISABLE is not set
+# CONFIG_BINFMT_EXEPATH is not set
+# CONFIG_NXFLAT is not set
+# CONFIG_ELF is not set
+CONFIG_BUILTIN=y
+# CONFIG_PIC is not set
+# CONFIG_SYMTAB_ORDEREDBYNAME is not set
+
+#
+# Library Routines
+#
+
+#
+# Standard C Library Options
+#
+CONFIG_STDIO_BUFFER_SIZE=32
+CONFIG_STDIO_LINEBUFFER=y
+CONFIG_NUNGET_CHARS=2
+CONFIG_LIB_HOMEDIR="/"
+# CONFIG_NOPRINTF_FIELDWIDTH is not set
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_LIB_RAND_ORDER=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
+CONFIG_LIBC_STRERROR=y
+# CONFIG_LIBC_STRERROR_SHORT is not set
+# CONFIG_LIBC_PERROR_STDOUT is not set
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_LIB_SENDFILE_BUFSIZE=512
+# CONFIG_ARCH_ROMGETC is not set
+CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y
+CONFIG_ARCH_MEMCPY=y
+# CONFIG_ARCH_MEMCMP is not set
+# CONFIG_ARCH_MEMMOVE is not set
+# CONFIG_ARCH_MEMSET is not set
+# CONFIG_MEMSET_OPTSPEED is not set
+# CONFIG_ARCH_STRCHR is not set
+# CONFIG_ARCH_STRCMP is not set
+# CONFIG_ARCH_STRCPY is not set
+# CONFIG_ARCH_STRNCPY is not set
+# CONFIG_ARCH_STRLEN is not set
+# CONFIG_ARCH_STRNLEN is not set
+# CONFIG_ARCH_BZERO is not set
+
+#
+# Non-standard Library Support
+#
+CONFIG_SCHED_WORKQUEUE=y
+CONFIG_SCHED_HPWORK=y
+CONFIG_SCHED_WORKPRIORITY=192
+CONFIG_SCHED_WORKPERIOD=5000
+CONFIG_SCHED_WORKSTACKSIZE=2000
+CONFIG_SCHED_LPWORK=y
+CONFIG_SCHED_LPWORKPRIORITY=50
+CONFIG_SCHED_LPWORKPERIOD=50000
+CONFIG_SCHED_LPWORKSTACKSIZE=2000
+# CONFIG_LIB_KBDCODEC is not set
+# CONFIG_LIB_SLCDCODEC is not set
+
+#
+# Basic CXX Support
+#
+CONFIG_C99_BOOL8=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=1024
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_CXXTEST is not set
+# CONFIG_EXAMPLES_DHCPD is not set
+# CONFIG_EXAMPLES_ELF is not set
+# CONFIG_EXAMPLES_FTPC is not set
+# CONFIG_EXAMPLES_FTPD is not set
+CONFIG_EXAMPLES_HELLO=y
+# CONFIG_EXAMPLES_HELLOXX is not set
+# CONFIG_EXAMPLES_JSON is not set
+# CONFIG_EXAMPLES_HIDKBD is not set
+# CONFIG_EXAMPLES_KEYPADTEST is not set
+# CONFIG_EXAMPLES_IGMP is not set
+# CONFIG_EXAMPLES_LCDRW is not set
+# CONFIG_EXAMPLES_MM is not set
+# CONFIG_EXAMPLES_MODBUS is not set
+CONFIG_EXAMPLES_MOUNT=y
+# CONFIG_EXAMPLES_MTDPART is not set
+# CONFIG_EXAMPLES_NRF24L01TERM is not set
+CONFIG_EXAMPLES_NSH=y
+# CONFIG_EXAMPLES_NULL is not set
+# CONFIG_EXAMPLES_NX is not set
+# CONFIG_EXAMPLES_NXCONSOLE is not set
+# CONFIG_EXAMPLES_NXFFS is not set
+# CONFIG_EXAMPLES_NXFLAT is not set
+# CONFIG_EXAMPLES_NXHELLO is not set
+# CONFIG_EXAMPLES_NXIMAGE is not set
+# CONFIG_EXAMPLES_NXLINES is not set
+# CONFIG_EXAMPLES_NXTEXT is not set
+# CONFIG_EXAMPLES_OSTEST is not set
+# CONFIG_EXAMPLES_PASHELLO is not set
+# CONFIG_EXAMPLES_PIPE is not set
+# CONFIG_EXAMPLES_POSIXSPAWN is not set
+# CONFIG_EXAMPLES_QENCODER is not set
+# CONFIG_EXAMPLES_RGMP is not set
+# CONFIG_EXAMPLES_ROMFS is not set
+# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_SLCD is not set
+# CONFIG_EXAMPLES_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART is not set
+# CONFIG_EXAMPLES_TCPECHO is not set
+# CONFIG_EXAMPLES_TELNETD is not set
+# CONFIG_EXAMPLES_THTTPD is not set
+# CONFIG_EXAMPLES_TIFF is not set
+# CONFIG_EXAMPLES_TOUCHSCREEN is not set
+# CONFIG_EXAMPLES_UDP is not set
+# CONFIG_EXAMPLES_UIP is not set
+# CONFIG_EXAMPLES_USBSERIAL is not set
+# CONFIG_EXAMPLES_USBMSC is not set
+# CONFIG_EXAMPLES_USBTERM is not set
+# CONFIG_EXAMPLES_WATCHDOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_TIFF is not set
+
+#
+# Interpreters
+#
+# CONFIG_INTERPRETERS_FICL is not set
+# CONFIG_INTERPRETERS_PCODE is not set
+
+#
+# Network Utilities
+#
+
+#
+# Networking Utilities
+#
+# CONFIG_NETUTILS_CODECS is not set
+# CONFIG_NETUTILS_DHCPC is not set
+# CONFIG_NETUTILS_DHCPD is not set
+# CONFIG_NETUTILS_FTPC is not set
+# CONFIG_NETUTILS_FTPD is not set
+# CONFIG_NETUTILS_JSON is not set
+# CONFIG_NETUTILS_RESOLV is not set
+# CONFIG_NETUTILS_SMTP is not set
+# CONFIG_NETUTILS_TELNETD is not set
+# CONFIG_NETUTILS_TFTPC is not set
+# CONFIG_NETUTILS_THTTPD is not set
+# CONFIG_NETUTILS_UIPLIB is not set
+# CONFIG_NETUTILS_WEBCLIENT is not set
+
+#
+# FreeModBus
+#
+# CONFIG_MODBUS is not set
+
+#
+# NSH Library
+#
+CONFIG_NSH_LIBRARY=y
+CONFIG_NSH_BUILTIN_APPS=y
+
+#
+# Disable Individual commands
+#
+# CONFIG_NSH_DISABLE_CAT is not set
+# CONFIG_NSH_DISABLE_CD is not set
+# CONFIG_NSH_DISABLE_CP is not set
+# CONFIG_NSH_DISABLE_DD is not set
+# CONFIG_NSH_DISABLE_ECHO is not set
+# CONFIG_NSH_DISABLE_EXEC is not set
+# CONFIG_NSH_DISABLE_EXIT is not set
+# CONFIG_NSH_DISABLE_FREE is not set
+# CONFIG_NSH_DISABLE_GET is not set
+# CONFIG_NSH_DISABLE_HELP is not set
+# CONFIG_NSH_DISABLE_HEXDUMP is not set
+# CONFIG_NSH_DISABLE_IFCONFIG is not set
+# CONFIG_NSH_DISABLE_KILL is not set
+# CONFIG_NSH_DISABLE_LOSETUP is not set
+# CONFIG_NSH_DISABLE_LS is not set
+# CONFIG_NSH_DISABLE_MB is not set
+# CONFIG_NSH_DISABLE_MKDIR is not set
+# CONFIG_NSH_DISABLE_MKFATFS is not set
+# CONFIG_NSH_DISABLE_MKFIFO is not set
+# CONFIG_NSH_DISABLE_MKRD is not set
+# CONFIG_NSH_DISABLE_MH is not set
+# CONFIG_NSH_DISABLE_MOUNT is not set
+# CONFIG_NSH_DISABLE_MW is not set
+# CONFIG_NSH_DISABLE_NSFMOUNT is not set
+# CONFIG_NSH_DISABLE_PS is not set
+# CONFIG_NSH_DISABLE_PING is not set
+# CONFIG_NSH_DISABLE_PUT is not set
+# CONFIG_NSH_DISABLE_PWD is not set
+# CONFIG_NSH_DISABLE_RM is not set
+# CONFIG_NSH_DISABLE_RMDIR is not set
+# CONFIG_NSH_DISABLE_SET is not set
+# CONFIG_NSH_DISABLE_SH is not set
+# CONFIG_NSH_DISABLE_SLEEP is not set
+# CONFIG_NSH_DISABLE_TEST is not set
+# CONFIG_NSH_DISABLE_UMOUNT is not set
+# CONFIG_NSH_DISABLE_UNSET is not set
+# CONFIG_NSH_DISABLE_USLEEP is not set
+# CONFIG_NSH_DISABLE_WGET is not set
+# CONFIG_NSH_DISABLE_XD is not set
+
+#
+# Configure Command Options
+#
+# CONFIG_NSH_CMDOPT_DF_H is not set
+CONFIG_NSH_CODECS_BUFSIZE=128
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_STRERROR=y
+CONFIG_NSH_LINELEN=128
+CONFIG_NSH_MAXARGUMENTS=12
+CONFIG_NSH_NESTDEPTH=8
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLEBG is not set
+CONFIG_NSH_ROMFSETC=y
+# CONFIG_NSH_ROMFSRC is not set
+CONFIG_NSH_ROMFSMOUNTPT="/etc"
+CONFIG_NSH_INITSCRIPT="init.d/rcS"
+CONFIG_NSH_ROMFSDEVNO=0
+CONFIG_NSH_ROMFSSECTSIZE=128
+CONFIG_NSH_ARCHROMFS=y
+CONFIG_NSH_FATDEVNO=1
+CONFIG_NSH_FATSECTSIZE=512
+CONFIG_NSH_FATNSECTORS=1024
+CONFIG_NSH_FATMOUNTPT="/tmp"
+CONFIG_NSH_CONSOLE=y
+
+#
+# USB Trace Support
+#
+# CONFIG_NSH_CONDEV is not set
+CONFIG_NSH_ARCHINIT=y
+
+#
+# NxWidgets/NxWM
+#
+
+#
+# System NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# I2C tool
+#
+CONFIG_SYSTEM_I2CTOOL=y
+CONFIG_I2CTOOL_MINBUS=0
+CONFIG_I2CTOOL_MAXBUS=3
+CONFIG_I2CTOOL_MINADDR=0x03
+CONFIG_I2CTOOL_MAXADDR=0x77
+CONFIG_I2CTOOL_MAXREGADDR=0xff
+CONFIG_I2CTOOL_DEFFREQ=4000000
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+# CONFIG_SYSTEM_FLASH_ERASEALL is not set
+
+#
+# readline()
+#
+CONFIG_SYSTEM_READLINE=y
+CONFIG_READLINE_ECHO=y
+
+#
+# Power Off
+#
+# CONFIG_SYSTEM_POWEROFF is not set
+
+#
+# RAMTRON
+#
+# CONFIG_SYSTEM_RAMTRON is not set
+
+#
+# SD Card
+#
+# CONFIG_SYSTEM_SDCARD is not set
+
+#
+# Sysinfo
+#
+CONFIG_SYSTEM_SYSINFO=y
+
+#
+# USB Monitor
+#
diff --git a/src/modules/position_estimator/module.mk b/nuttx-configs/aerocore/nsh/setenv.sh
old mode 100644
new mode 100755
similarity index 51%
rename from src/modules/position_estimator/module.mk
rename to nuttx-configs/aerocore/nsh/setenv.sh
index f64095d9d1..2327f38a1b
--- a/src/modules/position_estimator/module.mk
+++ b/nuttx-configs/aerocore/nsh/setenv.sh
@@ -1,6 +1,8 @@
-############################################################################
+#!/bin/bash
+# configs/aerocore/nsh/setenv.sh
#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -12,7 +14,7 @@
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
+# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
@@ -29,16 +31,37 @@
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
-############################################################################
-#
-# Makefile to build the position estimator
-#
+if [ "$_" = "$0" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
-MODULE_COMMAND = position_estimator
+WD=`pwd`
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
-# XXX this should be converted to a deamon, its a pretty bad example app
-MODULE_PRIORITY = SCHED_PRIORITY_DEFAULT
-MODULE_STACKSIZE = 4096
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
-SRCS = position_estimator_main.c
+# This the Cygwin path to the location where I installed the RIDE
+# toolchain under windows. You will also have to edit this if you install
+# the RIDE toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
+
+# This the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# This the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx-configs/aerocore/scripts/ld.script b/nuttx-configs/aerocore/scripts/ld.script
new file mode 100644
index 0000000000..968d3127ff
--- /dev/null
+++ b/nuttx-configs/aerocore/scripts/ld.script
@@ -0,0 +1,150 @@
+/****************************************************************************
+ * configs/aerocore/common/ld.script
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/* The STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and
+ * 256Kb of SRAM. SRAM is split up into three blocks:
+ *
+ * 1) 112Kb of SRAM beginning at address 0x2000:0000
+ * 2) 16Kb of SRAM beginning at address 0x2001:c000
+ * 3) 64Kb of SRAM beginning at address 0x2002:0000
+ * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x4000 of flash is reserved for the bootloader.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
+ ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
+}
+
+OUTPUT_ARCH(arm)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+
+ /*
+ * This is a hack to make the newlib libm __errno() call
+ * use the NuttX get_errno_ptr() function.
+ */
+ __errno = get_errno_ptr;
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Construction data for parameters.
+ */
+ __param ALIGN(4): {
+ __param_start = ABSOLUTE(.);
+ KEEP(*(__param*))
+ __param_end = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/Tools/px4params/px_process_params.py b/nuttx-configs/aerocore/src/Makefile
old mode 100755
new mode 100644
similarity index 57%
rename from Tools/px4params/px_process_params.py
rename to nuttx-configs/aerocore/src/Makefile
index 7799f63484..859ba4ab23
--- a/Tools/px4params/px_process_params.py
+++ b/nuttx-configs/aerocore/src/Makefile
@@ -1,7 +1,8 @@
-#!/usr/bin/env python
############################################################################
+# configs/aerocore/src/Makefile
#
-# Copyright (C) 2013 PX4 Development Team. All rights reserved.
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -13,7 +14,7 @@
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
+# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
@@ -32,36 +33,52 @@
#
############################################################################
-#
-# PX4 paramers processor (main executable file)
-#
-# It scans src/ subdirectory of the project, collects all parameters
-# definitions, and outputs list of parameters in XML and DokuWiki formats.
-#
+-include $(TOPDIR)/Make.defs
-import scanner
-import srcparser
-import output_xml
-import output_dokuwiki_tables
-import output_dokuwiki_listings
+CFLAGS += -I$(TOPDIR)/sched
-# Initialize parser
-prs = srcparser.Parser()
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
-# Scan directories, and parse the files
-sc = scanner.Scanner()
-sc.ScanDir("../../src", prs)
-groups = prs.GetParamGroups()
+CSRCS = empty.c
+COBJS = $(CSRCS:.c=$(OBJEXT))
-# Output into XML
-out = output_xml.XMLOutput(groups)
-out.Save("parameters.xml")
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
-# Output to DokuWiki listings
-#out = output_dokuwiki_listings.DokuWikiListingsOutput(groups)
-#out.Save("parameters.wiki")
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ $(call ARCHIVE, $@, $(OBJS))
+
+.depend: Makefile $(SRCS)
+ $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ $(Q) touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, libboard$(LIBEXT))
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
-# Output to DokuWiki tables
-out = output_dokuwiki_tables.DokuWikiTablesOutput(groups)
-out.Save("parameters.wiki")
-out.SaveRpc("parameters.wikirpc.xml")
diff --git a/nuttx-configs/aerocore/src/empty.c b/nuttx-configs/aerocore/src/empty.c
new file mode 100644
index 0000000000..ace900866c
--- /dev/null
+++ b/nuttx-configs/aerocore/src/empty.c
@@ -0,0 +1,4 @@
+/*
+ * There are no source files here, but libboard.a can't be empty, so
+ * we have this empty source file to keep it company.
+ */
diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index 1dc96b3c3f..bc0c120679 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -405,7 +405,7 @@ CONFIG_SIG_SIGWORK=4
CONFIG_MAX_TASKS=32
CONFIG_MAX_TASK_ARGS=10
CONFIG_NPTHREAD_KEYS=4
-CONFIG_NFILE_DESCRIPTORS=32
+CONFIG_NFILE_DESCRIPTORS=38
CONFIG_NFILE_STREAMS=8
CONFIG_NAME_MAX=32
CONFIG_PREALLOC_MQ_MSGS=4
@@ -417,8 +417,8 @@ CONFIG_PREALLOC_TIMERS=50
#
# Stack and heap information
#
-CONFIG_IDLETHREAD_STACKSIZE=6000
-CONFIG_USERMAIN_STACKSIZE=4096
+CONFIG_IDLETHREAD_STACKSIZE=4096
+CONFIG_USERMAIN_STACKSIZE=3500
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_PTHREAD_STACK_DEFAULT=2048
@@ -504,8 +504,8 @@ CONFIG_MTD_BYTE_WRITE=y
#
# USART1 Configuration
#
-CONFIG_USART1_RXBUFSIZE=512
-CONFIG_USART1_TXBUFSIZE=512
+CONFIG_USART1_RXBUFSIZE=256
+CONFIG_USART1_TXBUFSIZE=128
CONFIG_USART1_BAUD=57600
CONFIG_USART1_BITS=8
CONFIG_USART1_PARITY=0
@@ -528,8 +528,8 @@ CONFIG_USART2_OFLOWCONTROL=y
#
# UART5 Configuration
#
-CONFIG_UART5_RXBUFSIZE=512
-CONFIG_UART5_TXBUFSIZE=512
+CONFIG_UART5_RXBUFSIZE=256
+CONFIG_UART5_TXBUFSIZE=128
CONFIG_UART5_BAUD=57600
CONFIG_UART5_BITS=8
CONFIG_UART5_PARITY=0
@@ -540,8 +540,8 @@ CONFIG_UART5_2STOP=0
#
# USART6 Configuration
#
-CONFIG_USART6_RXBUFSIZE=512
-CONFIG_USART6_TXBUFSIZE=512
+CONFIG_USART6_RXBUFSIZE=128
+CONFIG_USART6_TXBUFSIZE=64
CONFIG_USART6_BAUD=57600
CONFIG_USART6_BITS=8
CONFIG_USART6_PARITY=0
@@ -720,11 +720,11 @@ CONFIG_SCHED_WORKQUEUE=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_WORKPRIORITY=192
CONFIG_SCHED_WORKPERIOD=5000
-CONFIG_SCHED_WORKSTACKSIZE=4000
+CONFIG_SCHED_WORKSTACKSIZE=2048
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKPERIOD=50000
-CONFIG_SCHED_LPWORKSTACKSIZE=4000
+CONFIG_SCHED_LPWORKSTACKSIZE=2048
# CONFIG_LIB_KBDCODEC is not set
# CONFIG_LIB_SLCDCODEC is not set
diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig
index 26222c255d..a982040c6d 100644
--- a/nuttx-configs/px4fmu-v2/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v2/nsh/defconfig
@@ -439,7 +439,7 @@ CONFIG_SIG_SIGWORK=4
CONFIG_MAX_TASKS=32
CONFIG_MAX_TASK_ARGS=10
CONFIG_NPTHREAD_KEYS=4
-CONFIG_NFILE_DESCRIPTORS=32
+CONFIG_NFILE_DESCRIPTORS=38
CONFIG_NFILE_STREAMS=8
CONFIG_NAME_MAX=32
CONFIG_PREALLOC_MQ_MSGS=4
@@ -796,11 +796,11 @@ CONFIG_SCHED_WORKQUEUE=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_WORKPRIORITY=192
CONFIG_SCHED_WORKPERIOD=5000
-CONFIG_SCHED_WORKSTACKSIZE=4000
+CONFIG_SCHED_WORKSTACKSIZE=2000
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKPERIOD=50000
-CONFIG_SCHED_LPWORKSTACKSIZE=4000
+CONFIG_SCHED_LPWORKSTACKSIZE=2000
# CONFIG_LIB_KBDCODEC is not set
# CONFIG_LIB_SLCDCODEC is not set
diff --git a/nuttx-configs/px4io-v2/include/board.h b/nuttx-configs/px4io-v2/include/board.h
index 4b9c906385..17e77918b4 100755
--- a/nuttx-configs/px4io-v2/include/board.h
+++ b/nuttx-configs/px4io-v2/include/board.h
@@ -103,8 +103,6 @@
#define GPIO_USART2_RTS 0xffffffff
#undef GPIO_USART2_CK
#define GPIO_USART2_CK 0xffffffff
-#undef GPIO_USART3_TX
-#define GPIO_USART3_TX 0xffffffff
#undef GPIO_USART3_CK
#define GPIO_USART3_CK 0xffffffff
#undef GPIO_USART3_CTS
diff --git a/nuttx-configs/px4io-v2/nsh/defconfig b/nuttx-configs/px4io-v2/nsh/defconfig
index 4111e70eba..e6563e5878 100755
--- a/nuttx-configs/px4io-v2/nsh/defconfig
+++ b/nuttx-configs/px4io-v2/nsh/defconfig
@@ -104,9 +104,9 @@ CONFIG_ARMV7M_CMNVECTOR=y
# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
#
CONFIG_STM32_DFU=n
-CONFIG_STM32_JTAG_FULL_ENABLE=y
+CONFIG_STM32_JTAG_FULL_ENABLE=n
CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
-CONFIG_STM32_JTAG_SW_ENABLE=n
+CONFIG_STM32_JTAG_SW_ENABLE=y
#
# Individual subsystems can be enabled:
diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp
index 524151c90d..41942aacd5 100644
--- a/src/drivers/airspeed/airspeed.cpp
+++ b/src/drivers/airspeed/airspeed.cpp
@@ -82,10 +82,12 @@ Airspeed::Airspeed(int bus, int address, unsigned conversion_interval, const cha
_buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows")),
_max_differential_pressure_pa(0),
_sensor_ok(false),
+ _last_published_sensor_ok(true), /* initialize differently to force publication */
_measure_ticks(0),
_collect_phase(false),
_diff_pres_offset(0.0f),
_airspeed_pub(-1),
+ _subsys_pub(-1),
_class_instance(-1),
_conversion_interval(conversion_interval),
_sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")),
@@ -149,8 +151,7 @@ Airspeed::init()
}
ret = OK;
- /* sensor is ok, but we don't really know if it is within range */
- _sensor_ok = true;
+
out:
return ret;
}
@@ -344,22 +345,6 @@ Airspeed::start()
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&Airspeed::cycle_trampoline, this, 1);
-
- /* notify about state change */
- struct subsystem_info_s info = {
- true,
- true,
- true,
- SUBSYSTEM_TYPE_DIFFPRESSURE
- };
- static orb_advert_t pub = -1;
-
- if (pub > 0) {
- orb_publish(ORB_ID(subsystem_info), pub, &info);
-
- } else {
- pub = orb_advertise(ORB_ID(subsystem_info), &info);
- }
}
void
@@ -368,12 +353,35 @@ Airspeed::stop()
work_cancel(HPWORK, &_work);
}
+void
+Airspeed::update_status()
+{
+ if (_sensor_ok != _last_published_sensor_ok) {
+ /* notify about state change */
+ struct subsystem_info_s info = {
+ true,
+ true,
+ _sensor_ok,
+ SUBSYSTEM_TYPE_DIFFPRESSURE
+ };
+
+ if (_subsys_pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), _subsys_pub, &info);
+ } else {
+ _subsys_pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ }
+
+ _last_published_sensor_ok = _sensor_ok;
+ }
+}
+
void
Airspeed::cycle_trampoline(void *arg)
{
Airspeed *dev = (Airspeed *)arg;
dev->cycle();
+ dev->update_status();
}
void
diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h
index 186602eda8..0b8e949c9d 100644
--- a/src/drivers/airspeed/airspeed.h
+++ b/src/drivers/airspeed/airspeed.h
@@ -118,14 +118,21 @@ protected:
virtual int measure() = 0;
virtual int collect() = 0;
+ /**
+ * Update the subsystem status
+ */
+ void update_status();
+
work_s _work;
float _max_differential_pressure_pa;
bool _sensor_ok;
+ bool _last_published_sensor_ok;
int _measure_ticks;
bool _collect_phase;
float _diff_pres_offset;
orb_advert_t _airspeed_pub;
+ orb_advert_t _subsys_pub;
int _class_instance;
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 2361f4dd18..5c502f6822 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -48,11 +48,14 @@
* The recognized number off cells, will be blinked 5 times in purple color.
* 2 Cells = 2 blinks
* ...
- * 5 Cells = 5 blinks
+ * 6 Cells = 6 blinks
* Now the Application will show the actual selected Flightmode, GPS-Fix and Battery Warnings and Alerts.
*
- * System disarmed:
- * The BlinkM should lit solid red.
+ * System disarmed and safe:
+ * The BlinkM should light solid cyan.
+ *
+ * System safety off but not armed:
+ * The BlinkM should light flashing orange
*
* System armed:
* One message is made of 4 Blinks and a pause in the same length as the 4 blinks.
@@ -67,10 +70,10 @@
* (X = on, _=off)
*
* The first 3 blinks indicates the status of the GPS-Signal (red):
- * 0-4 satellites = X-X-X-X-_-_-_-_-_-_-
- * 5 satellites = X-X-_-X-_-_-_-_-_-_-
- * 6 satellites = X-_-_-X-_-_-_-_-_-_-
- * >=7 satellites = _-_-_-X-_-_-_-_-_-_-
+ * 0-4 satellites = X-X-X-X-X-_-_-_-_-_-
+ * 5 satellites = X-X-_-X-X-_-_-_-_-_-
+ * 6 satellites = X-_-_-X-X-_-_-_-_-_-
+ * >=7 satellites = _-_-_-X-X-_-_-_-_-_-
* If no GPS is found the first 3 blinks are white
*
* The fourth Blink indicates the Flightmode:
@@ -119,6 +122,7 @@
#include
#include
#include
+#include
static const float MAX_CELL_VOLTAGE = 4.3f;
static const int LED_ONTIME = 120;
@@ -166,10 +170,12 @@ private:
enum ledColors {
LED_OFF,
LED_RED,
+ LED_ORANGE,
LED_YELLOW,
LED_PURPLE,
LED_GREEN,
LED_BLUE,
+ LED_CYAN,
LED_WHITE,
LED_AMBER
};
@@ -188,6 +194,26 @@ private:
bool systemstate_run;
+ int vehicle_status_sub_fd;
+ int vehicle_control_mode_sub_fd;
+ int vehicle_gps_position_sub_fd;
+ int actuator_armed_sub_fd;
+ int safety_sub_fd;
+
+ int num_of_cells;
+ int detected_cells_runcount;
+
+ int t_led_color[8];
+ int t_led_blink;
+ int led_thread_runcount;
+ int led_interval;
+
+ bool topic_initialized;
+ bool detected_cells_blinked;
+ bool led_thread_ready;
+
+ int num_of_used_sats;
+
void setLEDColor(int ledcolor);
static void led_trampoline(void *arg);
void led();
@@ -259,7 +285,22 @@ BlinkM::BlinkM(int bus, int blinkm) :
led_color_7(LED_OFF),
led_color_8(LED_OFF),
led_blink(LED_NOBLINK),
- systemstate_run(false)
+ systemstate_run(false),
+ vehicle_status_sub_fd(-1),
+ vehicle_control_mode_sub_fd(-1),
+ vehicle_gps_position_sub_fd(-1),
+ actuator_armed_sub_fd(-1),
+ safety_sub_fd(-1),
+ num_of_cells(0),
+ detected_cells_runcount(0),
+ t_led_color({0}),
+ t_led_blink(0),
+ led_thread_runcount(0),
+ led_interval(1000),
+ topic_initialized(false),
+ detected_cells_blinked(false),
+ led_thread_ready(true),
+ num_of_used_sats(0)
{
memset(&_work, 0, sizeof(_work));
}
@@ -376,42 +417,22 @@ void
BlinkM::led()
{
- static int vehicle_status_sub_fd;
- static int vehicle_control_mode_sub_fd;
- static int vehicle_gps_position_sub_fd;
- static int actuator_armed_sub_fd;
-
- static int num_of_cells = 0;
- static int detected_cells_runcount = 0;
-
- static int t_led_color[8] = { 0, 0, 0, 0, 0, 0, 0, 0};
- static int t_led_blink = 0;
- static int led_thread_runcount=0;
- static int led_interval = 1000;
-
- static int no_data_vehicle_status = 0;
- static int no_data_vehicle_control_mode = 0;
- static int no_data_actuator_armed = 0;
- static int no_data_vehicle_gps_position = 0;
-
- static bool topic_initialized = false;
- static bool detected_cells_blinked = false;
- static bool led_thread_ready = true;
-
- int num_of_used_sats = 0;
-
if(!topic_initialized) {
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
- orb_set_interval(vehicle_status_sub_fd, 1000);
+ orb_set_interval(vehicle_status_sub_fd, 250);
vehicle_control_mode_sub_fd = orb_subscribe(ORB_ID(vehicle_control_mode));
- orb_set_interval(vehicle_control_mode_sub_fd, 1000);
+ orb_set_interval(vehicle_control_mode_sub_fd, 250);
actuator_armed_sub_fd = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(actuator_armed_sub_fd, 1000);
+ orb_set_interval(actuator_armed_sub_fd, 250);
vehicle_gps_position_sub_fd = orb_subscribe(ORB_ID(vehicle_gps_position));
- orb_set_interval(vehicle_gps_position_sub_fd, 1000);
+ orb_set_interval(vehicle_gps_position_sub_fd, 250);
+
+ /* Subscribe to safety topic */
+ safety_sub_fd = orb_subscribe(ORB_ID(safety));
+ orb_set_interval(safety_sub_fd, 250);
topic_initialized = true;
}
@@ -433,7 +454,9 @@ BlinkM::led()
if(num_of_cells > 4) {
t_led_color[4] = LED_PURPLE;
}
- t_led_color[5] = LED_OFF;
+ if(num_of_cells > 5) {
+ t_led_color[5] = LED_PURPLE;
+ }
t_led_color[6] = LED_OFF;
t_led_color[7] = LED_OFF;
t_led_blink = LED_BLINK;
@@ -467,17 +490,25 @@ BlinkM::led()
struct vehicle_control_mode_s vehicle_control_mode;
struct actuator_armed_s actuator_armed;
struct vehicle_gps_position_s vehicle_gps_position_raw;
+ struct safety_s safety;
memset(&vehicle_status_raw, 0, sizeof(vehicle_status_raw));
memset(&vehicle_gps_position_raw, 0, sizeof(vehicle_gps_position_raw));
+ memset(&safety, 0, sizeof(safety));
bool new_data_vehicle_status;
bool new_data_vehicle_control_mode;
bool new_data_actuator_armed;
bool new_data_vehicle_gps_position;
+ bool new_data_safety;
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
+ int no_data_vehicle_status = 0;
+ int no_data_vehicle_control_mode = 0;
+ int no_data_actuator_armed = 0;
+ int no_data_vehicle_gps_position = 0;
+
if (new_data_vehicle_status) {
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub_fd, &vehicle_status_raw);
no_data_vehicle_status = 0;
@@ -520,7 +551,12 @@ BlinkM::led()
no_data_vehicle_gps_position = 3;
}
+ /* update safety topic */
+ orb_check(safety_sub_fd, &new_data_safety);
+ if (new_data_safety) {
+ orb_copy(ORB_ID(safety), safety_sub_fd, &safety);
+ }
/* get number of used satellites in navigation */
num_of_used_sats = 0;
@@ -541,19 +577,7 @@ BlinkM::led()
printf(" cells found:%d\n", num_of_cells);
} else {
- if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
- /* LED Pattern for battery low warning */
- led_color_1 = LED_YELLOW;
- led_color_2 = LED_YELLOW;
- led_color_3 = LED_YELLOW;
- led_color_4 = LED_YELLOW;
- led_color_5 = LED_YELLOW;
- led_color_6 = LED_YELLOW;
- led_color_7 = LED_YELLOW;
- led_color_8 = LED_YELLOW;
- led_blink = LED_BLINK;
-
- } else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) {
+ if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) {
/* LED Pattern for battery critical alerting */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
@@ -565,21 +589,56 @@ BlinkM::led()
led_color_8 = LED_RED;
led_blink = LED_BLINK;
+ } else if(vehicle_status_raw.rc_signal_lost) {
+ /* LED Pattern for FAILSAFE */
+ led_color_1 = LED_BLUE;
+ led_color_2 = LED_BLUE;
+ led_color_3 = LED_BLUE;
+ led_color_4 = LED_BLUE;
+ led_color_5 = LED_BLUE;
+ led_color_6 = LED_BLUE;
+ led_color_7 = LED_BLUE;
+ led_color_8 = LED_BLUE;
+ led_blink = LED_BLINK;
+
+ } else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
+ /* LED Pattern for battery low warning */
+ led_color_1 = LED_YELLOW;
+ led_color_2 = LED_YELLOW;
+ led_color_3 = LED_YELLOW;
+ led_color_4 = LED_YELLOW;
+ led_color_5 = LED_YELLOW;
+ led_color_6 = LED_YELLOW;
+ led_color_7 = LED_YELLOW;
+ led_color_8 = LED_YELLOW;
+ led_blink = LED_BLINK;
+
} else {
/* no battery warnings here */
if(actuator_armed.armed == false) {
/* system not armed */
- led_color_1 = LED_RED;
- led_color_2 = LED_RED;
- led_color_3 = LED_RED;
- led_color_4 = LED_RED;
- led_color_5 = LED_RED;
- led_color_6 = LED_RED;
- led_color_7 = LED_RED;
- led_color_8 = LED_RED;
- led_blink = LED_NOBLINK;
-
+ if(safety.safety_off){
+ led_color_1 = LED_ORANGE;
+ led_color_2 = LED_ORANGE;
+ led_color_3 = LED_ORANGE;
+ led_color_4 = LED_ORANGE;
+ led_color_5 = LED_ORANGE;
+ led_color_6 = LED_ORANGE;
+ led_color_7 = LED_ORANGE;
+ led_color_8 = LED_ORANGE;
+ led_blink = LED_BLINK;
+ }else{
+ led_color_1 = LED_CYAN;
+ led_color_2 = LED_CYAN;
+ led_color_3 = LED_CYAN;
+ led_color_4 = LED_CYAN;
+ led_color_5 = LED_CYAN;
+ led_color_6 = LED_CYAN;
+ led_color_7 = LED_CYAN;
+ led_color_8 = LED_CYAN;
+ led_blink = LED_NOBLINK;
+ }
} else {
/* armed system - initial led pattern */
led_color_1 = LED_RED;
@@ -593,23 +652,22 @@ BlinkM::led()
led_blink = LED_BLINK;
if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
-
- //XXX please check
- if (vehicle_control_mode.flag_control_position_enabled)
+ /* indicate main control state */
+ if (vehicle_status_raw.main_state == MAIN_STATE_POSCTL)
led_color_4 = LED_GREEN;
- else if (vehicle_control_mode.flag_control_velocity_enabled)
+ else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO)
led_color_4 = LED_BLUE;
- else if (vehicle_control_mode.flag_control_attitude_enabled)
+ else if (vehicle_status_raw.main_state == MAIN_STATE_ALTCTL)
led_color_4 = LED_YELLOW;
- else if (vehicle_control_mode.flag_control_manual_enabled)
- led_color_4 = LED_AMBER;
+ else if (vehicle_status_raw.main_state == MAIN_STATE_MANUAL)
+ led_color_4 = LED_WHITE;
else
led_color_4 = LED_OFF;
-
+ led_color_5 = led_color_4;
}
if(new_data_vehicle_gps_position || no_data_vehicle_gps_position < 3) {
- /* handling used sat�s */
+ /* handling used satus */
if(num_of_used_sats >= 7) {
led_color_1 = LED_OFF;
led_color_2 = LED_OFF;
@@ -690,8 +748,11 @@ void BlinkM::setLEDColor(int ledcolor) {
case LED_RED: // red
set_rgb(255,0,0);
break;
+ case LED_ORANGE: // orange
+ set_rgb(255,150,0);
+ break;
case LED_YELLOW: // yellow
- set_rgb(255,70,0);
+ set_rgb(200,200,0);
break;
case LED_PURPLE: // purple
set_rgb(255,0,255);
@@ -702,11 +763,14 @@ void BlinkM::setLEDColor(int ledcolor) {
case LED_BLUE: // blue
set_rgb(0,0,255);
break;
+ case LED_CYAN: // cyan
+ set_rgb(0,128,128);
+ break;
case LED_WHITE: // white
set_rgb(255,255,255);
break;
case LED_AMBER: // amber
- set_rgb(255,20,0);
+ set_rgb(255,65,0);
break;
}
}
diff --git a/src/drivers/boards/aerocore/aerocore_init.c b/src/drivers/boards/aerocore/aerocore_init.c
new file mode 100644
index 0000000000..4e3ba2d7e4
--- /dev/null
+++ b/src/drivers/boards/aerocore/aerocore_init.c
@@ -0,0 +1,282 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file aerocore_init.c
+ *
+ * AeroCore-specific early startup code. This file implements the
+ * nsh_archinitialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialisation.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include
+
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include "board_config.h"
+#include
+
+#include
+
+#include
+#include
+
+#include
+#include
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+#if defined(CONFIG_FAT_DMAMEMORY)
+# if !defined(CONFIG_GRAN) || !defined(CONFIG_FAT_DMAMEMORY)
+# error microSD DMA support requires CONFIG_GRAN
+# endif
+
+static GRAN_HANDLE dma_allocator;
+
+/*
+ * The DMA heap size constrains the total number of things that can be
+ * ready to do DMA at a time.
+ *
+ * For example, FAT DMA depends on one sector-sized buffer per filesystem plus
+ * one sector-sized buffer per file.
+ *
+ * We use a fundamental alignment / granule size of 64B; this is sufficient
+ * to guarantee alignment for the largest STM32 DMA burst (16 beats x 32bits).
+ */
+static uint8_t g_dma_heap[8192] __attribute__((aligned(64)));
+static perf_counter_t g_dma_perf;
+
+static void
+dma_alloc_init(void)
+{
+ dma_allocator = gran_initialize(g_dma_heap,
+ sizeof(g_dma_heap),
+ 7, /* 128B granule - must be > alignment (XXX bug?) */
+ 6); /* 64B alignment */
+ if (dma_allocator == NULL) {
+ message("[boot] DMA allocator setup FAILED");
+ } else {
+ g_dma_perf = perf_alloc(PC_COUNT, "DMA allocations");
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/*
+ * DMA-aware allocator stubs for the FAT filesystem.
+ */
+
+__EXPORT void *fat_dma_alloc(size_t size);
+__EXPORT void fat_dma_free(FAR void *memory, size_t size);
+
+void *
+fat_dma_alloc(size_t size)
+{
+ perf_count(g_dma_perf);
+ return gran_alloc(dma_allocator, size);
+}
+
+void
+fat_dma_free(FAR void *memory, size_t size)
+{
+ gran_free(dma_allocator, memory, size);
+}
+
+#else
+
+# define dma_alloc_init()
+
+#endif
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void
+stm32_boardinitialize(void)
+{
+ /* configure SPI interfaces */
+ stm32_spiinitialize();
+
+ /* configure LEDs */
+ up_ledinit();
+}
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+static struct spi_dev_s *spi3;
+static struct spi_dev_s *spi4;
+
+#include
+
+#ifdef __cplusplus
+__EXPORT int matherr(struct __exception *e)
+{
+ return 1;
+}
+#else
+__EXPORT int matherr(struct exception *e)
+{
+ return 1;
+}
+#endif
+
+__EXPORT int nsh_archinitialize(void)
+{
+
+ /* configure ADC pins */
+ stm32_configgpio(GPIO_ADC1_IN10); /* used by VBUS valid */
+ stm32_configgpio(GPIO_ADC1_IN11); /* J1 breakout */
+ stm32_configgpio(GPIO_ADC1_IN12); /* J1 breakout */
+ stm32_configgpio(GPIO_ADC1_IN13); /* J1 breakout */
+
+ /* configure the high-resolution time/callout interface */
+ hrt_init();
+
+ /* configure the DMA allocator */
+ dma_alloc_init();
+
+ /* configure CPU load estimation */
+#ifdef CONFIG_SCHED_INSTRUMENTATION
+ cpuload_initialize_once();
+#endif
+
+ /* set up the serial DMA polling */
+ static struct hrt_call serial_dma_call;
+ struct timespec ts;
+
+ /*
+ * Poll at 1ms intervals for received bytes that have not triggered
+ * a DMA event.
+ */
+ ts.tv_sec = 0;
+ ts.tv_nsec = 1000000;
+
+ hrt_call_every(&serial_dma_call,
+ ts_to_abstime(&ts),
+ ts_to_abstime(&ts),
+ (hrt_callout)stm32_serial_dma_poll,
+ NULL);
+
+ /* initial LED state */
+ drv_led_start();
+ led_off(LED_AMBER);
+
+ /* Configure Sensors on SPI bus #3 */
+ spi3 = up_spiinitialize(3);
+ if (!spi3) {
+ message("[boot] FAILED to initialize SPI port 3\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+ /* Default: 1MHz, 8 bits, Mode 3 */
+ SPI_SETFREQUENCY(spi3, 10000000);
+ SPI_SETBITS(spi3, 8);
+ SPI_SETMODE(spi3, SPIDEV_MODE3);
+ SPI_SELECT(spi3, PX4_SPIDEV_GYRO, false);
+ SPI_SELECT(spi3, PX4_SPIDEV_ACCEL_MAG, false);
+ SPI_SELECT(spi3, PX4_SPIDEV_BARO, false);
+ up_udelay(20);
+ message("[boot] Initialized SPI port 3 (SENSORS)\n");
+
+ /* Configure FRAM on SPI bus #4 */
+ spi4 = up_spiinitialize(4);
+ if (!spi4) {
+ message("[boot] FAILED to initialize SPI port 4\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+ /* Default: ~10MHz, 8 bits, Mode 3 */
+ SPI_SETFREQUENCY(spi4, 10 * 1000 * 1000);
+ SPI_SETBITS(spi4, 8);
+ SPI_SETMODE(spi4, SPIDEV_MODE0);
+ SPI_SELECT(spi4, SPIDEV_FLASH, false);
+ message("[boot] Initialized SPI port 4 (FRAM)\n");
+
+ return OK;
+}
diff --git a/src/drivers/boards/aerocore/aerocore_led.c b/src/drivers/boards/aerocore/aerocore_led.c
new file mode 100644
index 0000000000..e40d1730c6
--- /dev/null
+++ b/src/drivers/boards/aerocore/aerocore_led.c
@@ -0,0 +1,121 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file aerocore_led.c
+ *
+ * AeroCore LED backend.
+ */
+
+#include
+
+#include
+
+#include "stm32.h"
+#include "board_config.h"
+
+#include
+
+/*
+ * Ideally we'd be able to get these from up_internal.h,
+ * but since we want to be able to disable the NuttX use
+ * of leds for system indication at will and there is no
+ * separate switch, we need to build independent of the
+ * CONFIG_ARCH_LEDS configuration switch.
+ */
+__BEGIN_DECLS
+extern void led_init();
+extern void led_on(int led);
+extern void led_off(int led);
+extern void led_toggle(int led);
+__END_DECLS
+
+__EXPORT void led_init()
+{
+ stm32_configgpio(GPIO_LED0);
+ stm32_configgpio(GPIO_LED1);
+}
+
+__EXPORT void led_on(int led)
+{
+ switch (led) {
+ case 0:
+ stm32_gpiowrite(GPIO_LED0, true);
+ break;
+
+ case 1:
+ stm32_gpiowrite(GPIO_LED1, true);
+ break;
+
+ default:
+ warnx("LED ID not recognized\n");
+ }
+}
+
+__EXPORT void led_off(int led)
+{
+ switch (led) {
+ case 0:
+ stm32_gpiowrite(GPIO_LED0, false);
+ break;
+
+ case 1:
+ stm32_gpiowrite(GPIO_LED1, false);
+ break;
+
+ default:
+ warnx("LED ID not recognized\n");
+ }
+}
+
+__EXPORT void led_toggle(int led)
+{
+ switch (led) {
+ case 0:
+ if (stm32_gpioread(GPIO_LED0))
+ stm32_gpiowrite(GPIO_LED0, false);
+ else
+ stm32_gpiowrite(GPIO_LED0, true);
+ break;
+
+ case 1:
+ if (stm32_gpioread(GPIO_LED1))
+ stm32_gpiowrite(GPIO_LED1, false);
+ else
+ stm32_gpiowrite(GPIO_LED1, true);
+ break;
+
+ default:
+ warnx("LED ID not recognized\n");
+ }
+}
diff --git a/src/drivers/boards/aerocore/aerocore_pwm_servo.c b/src/drivers/boards/aerocore/aerocore_pwm_servo.c
new file mode 100644
index 0000000000..251eaff7b4
--- /dev/null
+++ b/src/drivers/boards/aerocore/aerocore_pwm_servo.c
@@ -0,0 +1,117 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * @file aerocore_pwm_servo.c
+ *
+ * Configuration data for the stm32 pwm_servo driver.
+ *
+ * Note that these arrays must always be fully-sized.
+ */
+
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+
+#include "board_config.h"
+
+__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
+ {
+ .base = STM32_TIM1_BASE,
+ .clock_register = STM32_RCC_APB2ENR,
+ .clock_bit = RCC_APB2ENR_TIM1EN,
+ .clock_freq = STM32_APB2_TIM1_CLKIN
+ },
+ {
+ .base = STM32_TIM3_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM3EN,
+ .clock_freq = STM32_APB1_TIM3_CLKIN
+ }
+};
+
+__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
+ {
+ .gpio = GPIO_TIM1_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM1_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM1_CH3OUT,
+ .timer_index = 0,
+ .timer_channel = 3,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM1_CH4OUT,
+ .timer_index = 0,
+ .timer_channel = 4,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH1OUT,
+ .timer_index = 1,
+ .timer_channel = 1,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH2OUT,
+ .timer_index = 1,
+ .timer_channel = 2,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH3OUT,
+ .timer_index = 1,
+ .timer_channel = 3,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH4OUT,
+ .timer_index = 1,
+ .timer_channel = 4,
+ .default_value = 1500,
+ }
+};
diff --git a/src/drivers/boards/aerocore/aerocore_spi.c b/src/drivers/boards/aerocore/aerocore_spi.c
new file mode 100644
index 0000000000..e329bd9d1a
--- /dev/null
+++ b/src/drivers/boards/aerocore/aerocore_spi.c
@@ -0,0 +1,183 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file aerocore_spi.c
+ *
+ * Board-specific SPI functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+#include "board_config.h"
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+__EXPORT void weak_function stm32_spiinitialize(void)
+{
+#ifdef CONFIG_STM32_SPI1
+ stm32_configgpio(GPIO_SPI1_NSS);
+ stm32_gpiowrite(GPIO_SPI1_NSS, 1);
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+ stm32_configgpio(GPIO_SPI2_NSS);
+ stm32_gpiowrite(GPIO_SPI2_NSS, 1);
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+ stm32_configgpio(GPIO_SPI_CS_GYRO);
+ stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
+ stm32_configgpio(GPIO_SPI_CS_BARO);
+
+ /* De-activate all peripherals,
+ * required for some peripheral
+ * state machines
+ */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+
+ stm32_configgpio(GPIO_EXTI_GYRO_DRDY);
+ stm32_configgpio(GPIO_EXTI_MAG_DRDY);
+ stm32_configgpio(GPIO_EXTI_ACCEL_DRDY);
+#endif
+
+#ifdef CONFIG_STM32_SPI4
+ stm32_configgpio(GPIO_SPI4_NSS);
+ stm32_gpiowrite(GPIO_SPI4_NSS, 1);
+#endif
+}
+
+#ifdef CONFIG_STM32_SPI1
+__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there is only one device broken-out so select it */
+ stm32_gpiowrite(GPIO_SPI1_NSS, !selected);
+}
+
+__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there is only one device broken-out so select it */
+ stm32_gpiowrite(GPIO_SPI2_NSS, !selected);
+}
+
+__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+__EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* SPI select is active low, so write !selected to select the device */
+
+ switch (devid) {
+ case PX4_SPIDEV_GYRO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ break;
+
+ case PX4_SPIDEV_ACCEL_MAG:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ break;
+
+ case PX4_SPIDEV_BARO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
+ break;
+
+ default:
+ break;
+ }
+}
+
+__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+
+#ifdef CONFIG_STM32_SPI4
+__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there can only be one device on this bus, so always select it */
+ stm32_gpiowrite(GPIO_SPI4_NSS, !selected);
+}
+
+__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ /* FRAM is always present */
+ return SPI_STATUS_PRESENT;
+}
+#endif
diff --git a/src/drivers/boards/aerocore/board_config.h b/src/drivers/boards/aerocore/board_config.h
new file mode 100644
index 0000000000..70142a3147
--- /dev/null
+++ b/src/drivers/boards/aerocore/board_config.h
@@ -0,0 +1,176 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file board_config.h
+ *
+ * AeroCore internal definitions
+ */
+
+#pragma once
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include
+#include
+#include
+
+__BEGIN_DECLS
+
+/* these headers are not C++ safe */
+#include
+#include
+
+#define UDID_START 0x1FFF7A10
+
+/****************************************************************************************************
+ * Definitions
+ ****************************************************************************************************/
+
+/* LEDs */
+#define GPIO_LED0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN9)
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN10)
+
+/* Gyro */
+#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0)
+#define SENSOR_BOARD_ROTATION_DEFAULT 3 /* SENSOR_BOARD_ROTATION_270_DEG */
+
+/* Accel & Mag */
+#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN1)
+#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN2)
+
+/* GPS */
+#define GPIO_GPS_NRESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
+#define GPIO_GPS_TIMEPULSE (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN4)
+#define GPS_DEFAULT_UART_PORT "/dev/ttyS0"
+
+/* SPI3--Sensors */
+#define PX4_SPI_BUS_SENSORS 3
+#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2)
+#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
+#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
+
+/* Nominal chip selects for devices on SPI bus #3 */
+#define PX4_SPIDEV_ACCEL_MAG 0
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_BARO 2
+
+/* User GPIOs broken out on J11 */
+#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN12)
+#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO8_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
+#define GPIO_GPIO9_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN15)
+#define GPIO_GPIO10_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_GPIO11_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN8)
+
+#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN12)
+#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO8_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
+#define GPIO_GPIO9_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15)
+#define GPIO_GPIO10_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_GPIO11_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
+
+/* PWM
+ *
+ * Eight PWM outputs are configured.
+ *
+ * Pins:
+ *
+ * CH1 : PA8 : TIM1_CH1
+ * CH2 : PA9 : TIM1_CH2
+ * CH3 : PA10 : TIM1_CH3
+ * CH4 : PA11 : TIM1_CH4
+ * CH5 : PC6 : TIM3_CH1
+ * CH6 : PC7 : TIM3_CH2
+ * CH7 : PC8 : TIM3_CH3
+ * CH8 : PC9 : TIM3_CH4
+ */
+#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_1
+#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_1
+#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_1
+#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_1
+#define GPIO_TIM3_CH1OUT GPIO_TIM3_CH1OUT_3
+#define GPIO_TIM3_CH2OUT GPIO_TIM3_CH2OUT_3
+#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_2
+#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_2
+
+/* High-resolution timer */
+#define HRT_TIMER 8 /* use timer 8 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+
+/* Tone Alarm (no onboard speaker )*/
+#define TONE_ALARM_TIMER 2 /* timer 2 */
+#define TONE_ALARM_CHANNEL 1 /* channel 1 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
+
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public data
+ ****************************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************************
+ * Public Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ****************************************************************************************************/
+
+extern void stm32_spiinitialize(void);
+
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/src/drivers/boards/aerocore/module.mk b/src/drivers/boards/aerocore/module.mk
new file mode 100644
index 0000000000..b53fe0a293
--- /dev/null
+++ b/src/drivers/boards/aerocore/module.mk
@@ -0,0 +1,8 @@
+#
+# Board-specific startup code for the AeroCore
+#
+
+SRCS = aerocore_init.c \
+ aerocore_pwm_servo.c \
+ aerocore_spi.c \
+ aerocore_led.c
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
index 02c26b5c0b..58273f2d29 100644
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -85,6 +85,8 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
+#define PX4_SPI_BUS_SENSORS 1
+
/*
* Use these in place of the spi_dev_e enumeration to
* select a specific SPI device on SPI1
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index 7cfca7656e..c2de1bfba0 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -107,6 +107,8 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
+#define PX4_SPI_BUS_SENSORS 1
+
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO 1
#define PX4_SPIDEV_ACCEL_MAG 2
diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp
index b157b3f181..6e2ebb1f7b 100644
--- a/src/drivers/device/cdev.cpp
+++ b/src/drivers/device/cdev.cpp
@@ -124,7 +124,7 @@ CDev::register_class_devname(const char *class_devname)
if (ret == OK) break;
} else {
char name[32];
- snprintf(name, sizeof(name), "%s%u", class_devname, class_instance);
+ snprintf(name, sizeof(name), "%s%d", class_devname, class_instance);
ret = register_driver(name, &fops, 0666, (void *)this);
if (ret == OK) break;
}
diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h
index f60964c2b1..5acd0d3434 100644
--- a/src/drivers/drv_gpio.h
+++ b/src/drivers/drv_gpio.h
@@ -94,6 +94,14 @@
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+/*
+ * AeroCore GPIO numbers and configuration.
+ *
+ */
+# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
+#endif
+
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
/* no GPIO driver on the PX4IOv1 board */
#endif
@@ -146,4 +154,4 @@
#define GPIO_SENSOR_RAIL_RESET GPIOC(13)
-#endif /* _DRV_GPIO_H */
\ No newline at end of file
+#endif /* _DRV_GPIO_H */
diff --git a/src/drivers/drv_gps.h b/src/drivers/drv_gps.h
index 06e3535b30..e14f4e00da 100644
--- a/src/drivers/drv_gps.h
+++ b/src/drivers/drv_gps.h
@@ -43,10 +43,14 @@
#include
#include
+#include "board_config.h"
+
#include "drv_sensor.h"
#include "drv_orb_dev.h"
+#ifndef GPS_DEFAULT_UART_PORT
#define GPS_DEFAULT_UART_PORT "/dev/ttyS3"
+#endif
#define GPS_DEVICE_PATH "/dev/gps"
diff --git a/src/drivers/drv_hrt.h b/src/drivers/drv_hrt.h
index d130d68b34..8bfc90c64b 100644
--- a/src/drivers/drv_hrt.h
+++ b/src/drivers/drv_hrt.h
@@ -41,6 +41,7 @@
#include
#include
+#include
#include
#include
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index 7a93e513ed..972573f9ff 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -199,6 +199,9 @@ ORB_DECLARE(output_pwm);
/** get the lockdown override flag to enable outputs in HIL */
#define PWM_SERVO_GET_DISABLE_LOCKDOWN _IOC(_PWM_SERVO_BASE, 22)
+/** force safety switch off (to disable use of safety switch) */
+#define PWM_SERVO_SET_FORCE_SAFETY_OFF _IOC(_PWM_SERVO_BASE, 23)
+
/*
*
*
diff --git a/src/drivers/drv_px4flow.h b/src/drivers/drv_px4flow.h
new file mode 100644
index 0000000000..bef02d54ef
--- /dev/null
+++ b/src/drivers/drv_px4flow.h
@@ -0,0 +1,84 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file Rangefinder driver interface.
+ */
+
+#ifndef _DRV_PX4FLOW_H
+#define _DRV_PX4FLOW_H
+
+#include
+#include
+
+#include "drv_sensor.h"
+#include "drv_orb_dev.h"
+
+#define PX4FLOW_DEVICE_PATH "/dev/px4flow"
+
+/**
+ * Optical flow in NED body frame in SI units.
+ *
+ * @see http://en.wikipedia.org/wiki/International_System_of_Units
+ */
+struct px4flow_report {
+
+ uint64_t timestamp; /**< in microseconds since system start */
+
+ int16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */
+ int16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */
+ float flow_comp_x_m; /**< speed over ground in meters, rotation-compensated */
+ float flow_comp_y_m; /**< speed over ground in meters, rotation-compensated */
+ float ground_distance_m; /**< Altitude / distance to ground in meters */
+ uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */
+ uint8_t sensor_id; /**< id of the sensor emitting the flow value */
+
+};
+
+/*
+ * ObjDev tag for px4flow data.
+ */
+ORB_DECLARE(optical_flow);
+
+/*
+ * ioctl() definitions
+ *
+ * px4flow drivers also implement the generic sensor driver
+ * interfaces from drv_sensor.h
+ */
+
+#define _PX4FLOWIOCBASE (0x7700)
+#define __PX4FLOWIOC(_n) (_IOC(_PX4FLOWIOCBASE, _n))
+
+
+#endif /* _DRV_PX4FLOW_H */
diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h
index cf91f70304..e45939b371 100644
--- a/src/drivers/drv_range_finder.h
+++ b/src/drivers/drv_range_finder.h
@@ -46,6 +46,10 @@
#define RANGE_FINDER_DEVICE_PATH "/dev/range_finder"
+enum RANGE_FINDER_TYPE {
+ RANGE_FINDER_TYPE_LASER = 0,
+};
+
/**
* range finder report structure. Reads from the device must be in multiples of this
* structure.
@@ -53,8 +57,11 @@
struct range_finder_report {
uint64_t timestamp;
uint64_t error_count;
- float distance; /** in meters */
- uint8_t valid; /** 1 == within sensor range, 0 = outside sensor range */
+ unsigned type; /**< type, following RANGE_FINDER_TYPE enum */
+ float distance; /**< in meters */
+ float minimum_distance; /**< minimum distance the sensor can measure */
+ float maximum_distance; /**< maximum distance the sensor can measure */
+ uint8_t valid; /**< 1 == within sensor range, 0 = outside sensor range */
};
/*
diff --git a/src/drivers/drv_tone_alarm.h b/src/drivers/drv_tone_alarm.h
index cb5fd53a5f..b7981e9c4b 100644
--- a/src/drivers/drv_tone_alarm.h
+++ b/src/drivers/drv_tone_alarm.h
@@ -147,6 +147,8 @@ enum {
TONE_BATTERY_WARNING_SLOW_TUNE,
TONE_BATTERY_WARNING_FAST_TUNE,
TONE_GPS_WARNING_TUNE,
+ TONE_ARMING_FAILURE_TUNE,
+ TONE_PARACHUTE_RELEASE_TUNE,
TONE_NUMBER_OF_TUNES
};
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index b6e80ce1d0..146a06e7cf 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -132,7 +132,6 @@ ETSAirspeed::measure()
if (OK != ret) {
perf_count(_comms_errors);
- log("i2c::transfer returned %d", ret);
}
return ret;
@@ -177,11 +176,14 @@ ETSAirspeed::collect()
_max_differential_pressure_pa = diff_pres_pa;
}
- // XXX we may want to smooth out the readings to remove noise.
differential_pressure_s report;
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
report.differential_pressure_pa = (float)diff_pres_pa;
+
+ // XXX we may want to smooth out the readings to remove noise.
+ report.differential_pressure_filtered_pa = (float)diff_pres_pa;
+ report.temperature = -1000.0f;
report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
@@ -205,14 +207,18 @@ ETSAirspeed::collect()
void
ETSAirspeed::cycle()
{
+ int ret;
+
/* collection phase? */
if (_collect_phase) {
/* perform collection */
- if (OK != collect()) {
+ ret = collect();
+ if (OK != ret) {
perf_count(_comms_errors);
/* restart the measurement state machine */
start();
+ _sensor_ok = false;
return;
}
@@ -236,8 +242,12 @@ ETSAirspeed::cycle()
}
/* measurement phase */
- if (OK != measure())
- log("measure error");
+ ret = measure();
+ if (OK != ret) {
+ debug("measure error");
+ }
+
+ _sensor_ok = (ret == OK);
/* next phase is collection */
_collect_phase = true;
@@ -308,7 +318,7 @@ fail:
g_dev = nullptr;
}
- errx(1, "driver start failed");
+ errx(1, "no ETS airspeed sensor connected");
}
/**
diff --git a/src/drivers/frsky_telemetry/frsky_data.c b/src/drivers/frsky_telemetry/frsky_data.c
index cfcf91e3fb..18de3f4dac 100644
--- a/src/drivers/frsky_telemetry/frsky_data.c
+++ b/src/drivers/frsky_telemetry/frsky_data.c
@@ -53,6 +53,8 @@
#include
#include
+#include
+
/* FrSky sensor hub data IDs */
#define FRSKY_ID_GPS_ALT_BP 0x01
#define FRSKY_ID_TEMP1 0x02
@@ -225,7 +227,7 @@ void frsky_send_frame2(int uart)
float course = 0, lat = 0, lon = 0, speed = 0, alt = 0;
char lat_ns = 0, lon_ew = 0;
int sec = 0;
- if (global_pos.global_valid) {
+ if (global_pos.timestamp != 0 && hrt_absolute_time() < global_pos.timestamp + 20000) {
time_t time_gps = global_pos.time_gps_usec / 1000000;
struct tm *tm_gps = gmtime(&time_gps);
diff --git a/src/drivers/frsky_telemetry/frsky_telemetry.c b/src/drivers/frsky_telemetry/frsky_telemetry.c
index 7b08ca69e9..6e08390436 100644
--- a/src/drivers/frsky_telemetry/frsky_telemetry.c
+++ b/src/drivers/frsky_telemetry/frsky_telemetry.c
@@ -222,7 +222,7 @@ int frsky_telemetry_main(int argc, char *argv[])
frsky_task = task_spawn_cmd("frsky_telemetry",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 2000,
frsky_telemetry_thread_main,
(const char **)argv);
diff --git a/src/drivers/frsky_telemetry/module.mk b/src/drivers/frsky_telemetry/module.mk
index 1632c74f75..9a49589ee5 100644
--- a/src/drivers/frsky_telemetry/module.mk
+++ b/src/drivers/frsky_telemetry/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = frsky_telemetry
SRCS = frsky_data.c \
frsky_telemetry.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index a736cbdf6b..6195cd6eab 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -56,6 +56,7 @@
#include
#include
#include
+#include
#include
#include
#include
@@ -63,6 +64,8 @@
#include
#include
+#include
+
#include "ubx.h"
#include "mtk.h"
@@ -76,12 +79,6 @@
#endif
static const int ERROR = -1;
-#ifndef CONFIG_SCHED_WORKQUEUE
-# error This requires CONFIG_SCHED_WORKQUEUE.
-#endif
-
-
-
class GPS : public device::CDev
{
public:
@@ -209,7 +206,8 @@ GPS::init()
goto out;
/* start the GPS driver worker task */
- _task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 2048, (main_t)&GPS::task_main_trampoline, nullptr);
+ _task = task_spawn_cmd("gps", SCHED_DEFAULT,
+ SCHED_PRIORITY_SLOW_DRIVER, 2000, (main_t)&GPS::task_main_trampoline, nullptr);
if (_task < 0) {
warnx("task start failed: %d", errno);
@@ -232,6 +230,11 @@ GPS::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSORIOCRESET:
cmd_reset();
break;
+
+ default:
+ /* give it to parent if no one wants it */
+ ret = CDev::ioctl(filp, cmd, arg);
+ break;
}
unlock();
@@ -271,14 +274,14 @@ GPS::task_main()
_report.timestamp_position = hrt_absolute_time();
_report.lat = (int32_t)47.378301e7f;
_report.lon = (int32_t)8.538777e7f;
- _report.alt = (int32_t)400e3f;
+ _report.alt = (int32_t)1200e3f;
_report.timestamp_variance = hrt_absolute_time();
_report.s_variance_m_s = 10.0f;
_report.p_variance_m = 10.0f;
_report.c_variance_rad = 0.1f;
_report.fix_type = 3;
- _report.eph_m = 10.0f;
- _report.epv_m = 10.0f;
+ _report.eph_m = 0.9f;
+ _report.epv_m = 1.8f;
_report.timestamp_velocity = hrt_absolute_time();
_report.vel_n_m_s = 0.0f;
_report.vel_e_m_s = 0.0f;
@@ -416,7 +419,14 @@ GPS::task_main()
void
GPS::cmd_reset()
{
- //XXX add reset?
+#ifdef GPIO_GPS_NRESET
+ warnx("Toggling GPS reset pin");
+ stm32_configgpio(GPIO_GPS_NRESET);
+ stm32_gpiowrite(GPIO_GPS_NRESET, 0);
+ usleep(100);
+ stm32_gpiowrite(GPIO_GPS_NRESET, 1);
+ warnx("Toggled GPS reset pin");
+#endif
}
void
diff --git a/src/drivers/gps/module.mk b/src/drivers/gps/module.mk
index 82c67d40a3..eb382c4b26 100644
--- a/src/drivers/gps/module.mk
+++ b/src/drivers/gps/module.mk
@@ -41,3 +41,5 @@ SRCS = gps.cpp \
gps_helper.cpp \
mtk.cpp \
ubx.cpp
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp
index c90ecbe281..680f00d97f 100644
--- a/src/drivers/gps/mtk.cpp
+++ b/src/drivers/gps/mtk.cpp
@@ -249,12 +249,18 @@ MTK::handle_message(gps_mtk_packet_t &packet)
warnx("mtk: unknown revision");
_gps_position->lat = 0;
_gps_position->lon = 0;
+
+ // Indicate this data is not usable and bail out
+ _gps_position->eph_m = 1000.0f;
+ _gps_position->epv_m = 1000.0f;
+ _gps_position->fix_type = 0;
+ return;
}
_gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm
_gps_position->fix_type = packet.fix_type;
- _gps_position->eph_m = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit
- _gps_position->epv_m = 0.0; //unknown in mtk custom mode
+ _gps_position->eph_m = packet.hdop / 100.0f; // from cm to m
+ _gps_position->epv_m = _gps_position->eph_m; // unknown in mtk custom mode, so we cheat with eph
_gps_position->vel_m_s = ((float)packet.ground_speed) * 1e-2f; // from cm/s to m/s
_gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad
_gps_position->satellites_visible = packet.satellites;
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index 0a047f38f1..55cc077fb6 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -122,7 +122,7 @@ private:
actuator_controls_s _controls;
static void task_main_trampoline(int argc, char *argv[]);
- void task_main() __attribute__((noreturn));
+ void task_main();
static int control_callback(uintptr_t handle,
uint8_t control_group,
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 4c85c0cdaa..fddba806e3 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -158,6 +158,7 @@ private:
int _class_instance;
orb_advert_t _mag_topic;
+ orb_advert_t _subsystem_pub;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
@@ -169,6 +170,8 @@ private:
int _bus; /**< the bus the device is connected to */
+ struct mag_report _last_report; /**< used for info() */
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -322,7 +325,9 @@ HMC5883::HMC5883(int bus) :
_reports(nullptr),
_range_scale(0), /* default range scale from counts to gauss */
_range_ga(1.3f),
+ _collect_phase(false),
_mag_topic(-1),
+ _subsystem_pub(-1),
_class_instance(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")),
_comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")),
@@ -713,7 +718,7 @@ HMC5883::cycle()
/* perform collection */
if (OK != collect()) {
- log("collection error");
+ debug("collection error");
/* restart the measurement state machine */
start();
return;
@@ -740,7 +745,7 @@ HMC5883::cycle()
/* measurement phase */
if (OK != measure())
- log("measure error");
+ debug("measure error");
/* next phase is collection */
_collect_phase = true;
@@ -870,6 +875,8 @@ HMC5883::collect()
}
}
+ _last_report = new_report;
+
/* post a report to the ring */
if (_reports->force(&new_report)) {
perf_count(_buffer_overflows);
@@ -1042,32 +1049,29 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
warnx("axes scaling: %.6f %.6f %.6f", (double)scaling[0], (double)scaling[1], (double)scaling[2]);
- /* set back to normal mode */
- /* Set to 1.1 Gauss */
- if (OK != ::ioctl(fd, MAGIOCSRANGE, 1)) {
- warnx("failed to set 1.1 Ga range");
- goto out;
- }
-
- if (OK != ::ioctl(fd, MAGIOCEXSTRAP, 0)) {
- warnx("failed to disable sensor calibration mode");
- goto out;
- }
-
/* set scaling in device */
mscale_previous.x_scale = scaling[0];
mscale_previous.y_scale = scaling[1];
mscale_previous.z_scale = scaling[2];
- if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_previous)) {
- warn("WARNING: failed to set new scale / offsets for mag");
- goto out;
- }
-
ret = OK;
out:
+ if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_previous)) {
+ warn("WARNING: failed to set new scale / offsets for mag");
+ }
+
+ /* set back to normal mode */
+ /* Set to 1.1 Gauss */
+ if (OK != ::ioctl(fd, MAGIOCSRANGE, 1)) {
+ warnx("failed to set 1.1 Ga range");
+ }
+
+ if (OK != ::ioctl(fd, MAGIOCEXSTRAP, 0)) {
+ warnx("failed to disable sensor calibration mode");
+ }
+
if (ret == OK) {
if (!check_scale()) {
warnx("mag scale calibration successfully finished.");
@@ -1136,13 +1140,12 @@ int HMC5883::check_calibration()
true,
_calibrated,
SUBSYSTEM_TYPE_MAG};
- static orb_advert_t pub = -1;
if (!(_pub_blocked)) {
- if (pub > 0) {
- orb_publish(ORB_ID(subsystem_info), pub, &info);
+ if (_subsystem_pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), _subsystem_pub, &info);
} else {
- pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ _subsystem_pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
}
}
@@ -1221,6 +1224,7 @@ HMC5883::print_info()
perf_print_counter(_comms_errors);
perf_print_counter(_buffer_overflows);
printf("poll interval: %u ticks\n", _measure_ticks);
+ printf("output (%.2f %.2f %.2f)\n", (double)_last_report.x, (double)_last_report.y, (double)_last_report.z);
printf("offsets (%.2f %.2f %.2f)\n", (double)_scale.x_offset, (double)_scale.y_offset, (double)_scale.z_offset);
printf("scaling (%.2f %.2f %.2f) 1/range_scale %.2f range_ga %.2f\n",
(double)_scale.x_scale, (double)_scale.y_scale, (double)_scale.z_scale,
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
index 90a7440159..1e779e8dc5 100644
--- a/src/drivers/hott/messages.cpp
+++ b/src/drivers/hott/messages.cpp
@@ -51,6 +51,8 @@
#include
#include
+#include
+
/* The board is very roughly 5 deg warmer than the surrounding air */
#define BOARD_TEMP_OFFSET_DEG 5
@@ -62,7 +64,6 @@ static int _airspeed_sub = -1;
static int _esc_sub = -1;
static orb_advert_t _esc_pub;
-struct esc_status_s _esc;
static bool _home_position_set = false;
static double _home_lat = 0.0d;
@@ -82,8 +83,6 @@ init_sub_messages(void)
void
init_pub_messages(void)
{
- memset(&_esc, 0, sizeof(_esc));
- _esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
}
void
@@ -106,23 +105,26 @@ publish_gam_message(const uint8_t *buffer)
size_t size = sizeof(msg);
memset(&msg, 0, size);
memcpy(&msg, buffer, size);
+ struct esc_status_s esc;
+ memset(&esc, 0, sizeof(esc));
+
+ // Publish it.
+ esc.timestamp = hrt_absolute_time();
+ esc.esc_count = 1;
+ esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
+
+ esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
+ esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
+ esc.esc[0].esc_temperature = msg.temperature1 - 20;
+ esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
+ esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
/* announce the esc if needed, just publish else */
if (_esc_pub > 0) {
- orb_publish(ORB_ID(esc_status), _esc_pub, &_esc);
+ orb_publish(ORB_ID(esc_status), _esc_pub, &esc);
} else {
- _esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
+ _esc_pub = orb_advertise(ORB_ID(esc_status), &esc);
}
-
- // Publish it.
- _esc.esc_count = 1;
- _esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
-
- _esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
- _esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
- _esc.esc[0].esc_temperature = msg.temperature1 - 20;
- _esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
- _esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
}
void
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 90c3db9ae9..37e72388be 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -34,6 +34,9 @@
/**
* @file l3gd20.cpp
* Driver for the ST L3GD20 MEMS gyro connected via SPI.
+ *
+ * Note: With the exception of the self-test feature, the ST L3G4200D is
+ * also supported by this driver.
*/
#include
@@ -89,9 +92,11 @@ static const int ERROR = -1;
#define ADDR_WHO_AM_I 0x0F
#define WHO_I_AM_H 0xD7
#define WHO_I_AM 0xD4
+#define WHO_I_AM_L3G4200D 0xD3 /* for L3G4200D */
#define ADDR_CTRL_REG1 0x20
#define REG1_RATE_LP_MASK 0xF0 /* Mask to guard partial register update */
+
/* keep lowpass low to avoid noise issues */
#define RATE_95HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4))
#define RATE_190HZ_LP_25HZ ((0<<7) | (1<<6) | (0<<5) | (1<<4))
@@ -166,9 +171,14 @@ static const int ERROR = -1;
#define FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
#define L3GD20_DEFAULT_RATE 760
+#define L3G4200D_DEFAULT_RATE 800
#define L3GD20_DEFAULT_RANGE_DPS 2000
#define L3GD20_DEFAULT_FILTER_FREQ 30
+#ifndef SENSOR_BOARD_ROTATION_DEFAULT
+#define SENSOR_BOARD_ROTATION_DEFAULT SENSOR_BOARD_ROTATION_270_DEG
+#endif
+
extern "C" { __EXPORT int l3gd20_main(int argc, char *argv[]); }
class L3GD20 : public device::SPI
@@ -216,6 +226,9 @@ private:
math::LowPassFilter2p _gyro_filter_y;
math::LowPassFilter2p _gyro_filter_z;
+ /* true if an L3G4200D is detected */
+ bool _is_l3g4200d;
+
/**
* Start automatic measurement.
*/
@@ -324,14 +337,15 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
_gyro_topic(-1),
_class_instance(-1),
_current_rate(0),
- _orientation(SENSOR_BOARD_ROTATION_270_DEG),
+ _orientation(SENSOR_BOARD_ROTATION_DEFAULT),
_read(0),
_sample_perf(perf_alloc(PC_ELAPSED, "l3gd20_read")),
_reschedules(perf_alloc(PC_COUNT, "l3gd20_reschedules")),
_errors(perf_alloc(PC_COUNT, "l3gd20_errors")),
_gyro_filter_x(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
_gyro_filter_y(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
- _gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ)
+ _gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
+ _is_l3g4200d(false)
{
// enable debug() calls
_debug_enabled = true;
@@ -413,14 +427,7 @@ L3GD20::probe()
/* verify that the device is attached and functioning, accept L3GD20 and L3GD20H */
if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
- #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
- _orientation = SENSOR_BOARD_ROTATION_270_DEG;
- #elif CONFIG_ARCH_BOARD_PX4FMU_V2
- _orientation = SENSOR_BOARD_ROTATION_270_DEG;
- #else
- #error This driver needs a board selection, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
- #endif
-
+ _orientation = SENSOR_BOARD_ROTATION_DEFAULT;
success = true;
}
@@ -430,6 +437,13 @@ L3GD20::probe()
success = true;
}
+ /* Detect the L3G4200D used on AeroCore */
+ if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM_L3G4200D) {
+ _is_l3g4200d = true;
+ _orientation = SENSOR_BOARD_ROTATION_DEFAULT;
+ success = true;
+ }
+
if (success)
return OK;
@@ -502,6 +516,9 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT:
+ if (_is_l3g4200d) {
+ return ioctl(filp, SENSORIOCSPOLLRATE, L3G4200D_DEFAULT_RATE);
+ }
return ioctl(filp, SENSORIOCSPOLLRATE, L3GD20_DEFAULT_RATE);
/* adjust to a legal polling interval in Hz */
@@ -683,23 +700,26 @@ L3GD20::set_samplerate(unsigned frequency)
uint8_t bits = REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
if (frequency == 0)
- frequency = 760;
+ frequency = _is_l3g4200d ? 800 : 760;
- /* use limits good for H or non-H models */
+ /*
+ * Use limits good for H or non-H models. Rates are slightly different
+ * for L3G4200D part but register settings are the same.
+ */
if (frequency <= 100) {
- _current_rate = 95;
+ _current_rate = _is_l3g4200d ? 100 : 95;
bits |= RATE_95HZ_LP_25HZ;
} else if (frequency <= 200) {
- _current_rate = 190;
+ _current_rate = _is_l3g4200d ? 200 : 190;
bits |= RATE_190HZ_LP_50HZ;
} else if (frequency <= 400) {
- _current_rate = 380;
+ _current_rate = _is_l3g4200d ? 400 : 380;
bits |= RATE_380HZ_LP_50HZ;
} else if (frequency <= 800) {
- _current_rate = 760;
+ _current_rate = _is_l3g4200d ? 800 : 760;
bits |= RATE_760HZ_LP_50HZ;
} else {
return -EINVAL;
@@ -772,7 +792,7 @@ L3GD20::reset()
* callback fast enough to not miss data. */
write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE);
- set_samplerate(0); // 760Hz
+ set_samplerate(0); // 760Hz or 800Hz
set_range(L3GD20_DEFAULT_RANGE_DPS);
set_driver_lowpass_filter(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ);
@@ -971,7 +991,7 @@ start()
errx(0, "already started");
/* create the driver */
- g_dev = new L3GD20(1 /* SPI bus 1 */, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
+ g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
if (g_dev == nullptr)
goto fail;
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 4dee7649bc..4ca8b5e42d 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -1793,7 +1793,7 @@ start()
errx(0, "already started");
/* create the driver */
- g_dev = new LSM303D(1 /* SPI dev 1 */, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
+ g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
if (g_dev == nullptr) {
warnx("failed instantiating LSM303D obj");
diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp
index c910e28908..5adb8cf698 100644
--- a/src/drivers/mb12xx/mb12xx.cpp
+++ b/src/drivers/mb12xx/mb12xx.cpp
@@ -37,7 +37,7 @@
*
* Driver for the Maxbotix sonar range finders connected via I2C.
*/
-
+
#include
#include
@@ -84,7 +84,7 @@
/* Device limits */
#define MB12XX_MIN_DISTANCE (0.20f)
#define MB12XX_MAX_DISTANCE (7.65f)
-
+
#define MB12XX_CONVERSION_INTERVAL 60000 /* 60ms */
/* oddly, ERROR is not defined for c++ */
@@ -102,17 +102,17 @@ class MB12XX : public device::I2C
public:
MB12XX(int bus = MB12XX_BUS, int address = MB12XX_BASEADDR);
virtual ~MB12XX();
-
+
virtual int init();
-
+
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
-
+
/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();
-
+
protected:
virtual int probe();
@@ -124,13 +124,13 @@ private:
bool _sensor_ok;
int _measure_ticks;
bool _collect_phase;
-
+
orb_advert_t _range_finder_topic;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
-
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -139,7 +139,7 @@ private:
* @return True if the device is present.
*/
int probe_address(uint8_t address);
-
+
/**
* Initialise the automatic measurement state machine and start it.
*
@@ -147,12 +147,12 @@ private:
* to make it more aggressive about resetting the bus in case of errors.
*/
void start();
-
+
/**
* Stop the automatic measurement state machine.
*/
void stop();
-
+
/**
* Set the min and max distance thresholds if you want the end points of the sensors
* range to be brought in at all, otherwise it will use the defaults MB12XX_MIN_DISTANCE
@@ -162,7 +162,7 @@ private:
void set_maximum_distance(float max);
float get_minimum_distance();
float get_maximum_distance();
-
+
/**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
@@ -177,8 +177,8 @@ private:
* @param arg Instance pointer for the driver that is polling.
*/
static void cycle_trampoline(void *arg);
-
-
+
+
};
/*
@@ -200,8 +200,8 @@ MB12XX::MB12XX(int bus, int address) :
_buffer_overflows(perf_alloc(PC_COUNT, "mb12xx_buffer_overflows"))
{
// enable debug() calls
- _debug_enabled = true;
-
+ _debug_enabled = false;
+
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
}
@@ -212,8 +212,9 @@ MB12XX::~MB12XX()
stop();
/* free any existing reports */
- if (_reports != nullptr)
+ if (_reports != nullptr) {
delete _reports;
+ }
}
int
@@ -222,22 +223,25 @@ MB12XX::init()
int ret = ERROR;
/* do I2C init (and probe) first */
- if (I2C::init() != OK)
+ if (I2C::init() != OK) {
goto out;
+ }
/* allocate basic report buffers */
_reports = new RingBuffer(2, sizeof(range_finder_report));
- if (_reports == nullptr)
+ if (_reports == nullptr) {
goto out;
+ }
/* get a publish handle on the range finder topic */
struct range_finder_report zero_report;
memset(&zero_report, 0, sizeof(zero_report));
_range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &zero_report);
- if (_range_finder_topic < 0)
+ if (_range_finder_topic < 0) {
debug("failed to create sensor_range_finder object. Did you start uOrb?");
+ }
ret = OK;
/* sensor is ok, but we don't really know if it is within range */
@@ -256,13 +260,13 @@ void
MB12XX::set_minimum_distance(float min)
{
_min_distance = min;
-}
+}
void
MB12XX::set_maximum_distance(float max)
{
_max_distance = max;
-}
+}
float
MB12XX::get_minimum_distance()
@@ -284,20 +288,20 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSORIOCSPOLLRATE: {
switch (arg) {
- /* switching to manual polling */
+ /* switching to manual polling */
case SENSOR_POLLRATE_MANUAL:
stop();
_measure_ticks = 0;
return OK;
- /* external signalling (DRDY) not supported */
+ /* external signalling (DRDY) not supported */
case SENSOR_POLLRATE_EXTERNAL:
- /* zero would be bad */
+ /* zero would be bad */
case 0:
return -EINVAL;
- /* set default/max polling rate */
+ /* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT: {
/* do we need to start internal polling? */
@@ -307,13 +311,14 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
_measure_ticks = USEC2TICK(MB12XX_CONVERSION_INTERVAL);
/* if we need to start the poll state machine, do it */
- if (want_start)
+ if (want_start) {
start();
+ }
return OK;
}
- /* adjust to a legal polling interval in Hz */
+ /* adjust to a legal polling interval in Hz */
default: {
/* do we need to start internal polling? */
bool want_start = (_measure_ticks == 0);
@@ -322,15 +327,17 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
unsigned ticks = USEC2TICK(1000000 / arg);
/* check against maximum rate */
- if (ticks < USEC2TICK(MB12XX_CONVERSION_INTERVAL))
+ if (ticks < USEC2TICK(MB12XX_CONVERSION_INTERVAL)) {
return -EINVAL;
+ }
/* update interval for next measurement */
_measure_ticks = ticks;
/* if we need to start the poll state machine, do it */
- if (want_start)
+ if (want_start) {
start();
+ }
return OK;
}
@@ -338,45 +345,49 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
}
case SENSORIOCGPOLLRATE:
- if (_measure_ticks == 0)
+ if (_measure_ticks == 0) {
return SENSOR_POLLRATE_MANUAL;
+ }
return (1000 / _measure_ticks);
case SENSORIOCSQUEUEDEPTH: {
- /* lower bound is mandatory, upper bound is a sanity check */
- if ((arg < 1) || (arg > 100))
- return -EINVAL;
-
- irqstate_t flags = irqsave();
- if (!_reports->resize(arg)) {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100)) {
+ return -EINVAL;
+ }
+
+ irqstate_t flags = irqsave();
+
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+
irqrestore(flags);
- return -ENOMEM;
+
+ return OK;
}
- irqrestore(flags);
-
- return OK;
- }
case SENSORIOCGQUEUEDEPTH:
return _reports->size();
-
+
case SENSORIOCRESET:
/* XXX implement this */
return -EINVAL;
-
- case RANGEFINDERIOCSETMINIUMDISTANCE:
- {
- set_minimum_distance(*(float *)arg);
- return 0;
- }
- break;
- case RANGEFINDERIOCSETMAXIUMDISTANCE:
- {
- set_maximum_distance(*(float *)arg);
- return 0;
- }
- break;
+
+ case RANGEFINDERIOCSETMINIUMDISTANCE: {
+ set_minimum_distance(*(float *)arg);
+ return 0;
+ }
+ break;
+
+ case RANGEFINDERIOCSETMAXIUMDISTANCE: {
+ set_maximum_distance(*(float *)arg);
+ return 0;
+ }
+ break;
+
default:
/* give it to the superclass */
return I2C::ioctl(filp, cmd, arg);
@@ -391,8 +402,9 @@ MB12XX::read(struct file *filp, char *buffer, size_t buflen)
int ret = 0;
/* buffer must be large enough */
- if (count < 1)
+ if (count < 1) {
return -ENOSPC;
+ }
/* if automatic measurement is enabled */
if (_measure_ticks > 0) {
@@ -453,14 +465,14 @@ MB12XX::measure()
uint8_t cmd = MB12XX_TAKE_RANGE_REG;
ret = transfer(&cmd, 1, nullptr, 0);
- if (OK != ret)
- {
+ if (OK != ret) {
perf_count(_comms_errors);
log("i2c::transfer returned %d", ret);
return ret;
}
+
ret = OK;
-
+
return ret;
}
@@ -468,32 +480,31 @@ int
MB12XX::collect()
{
int ret = -EIO;
-
+
/* read from the sensor */
uint8_t val[2] = {0, 0};
-
+
perf_begin(_sample_perf);
-
+
ret = transfer(nullptr, 0, &val[0], 2);
-
- if (ret < 0)
- {
+
+ if (ret < 0) {
log("error reading from sensor: %d", ret);
perf_count(_comms_errors);
perf_end(_sample_perf);
return ret;
}
-
+
uint16_t distance = val[0] << 8 | val[1];
- float si_units = (distance * 1.0f)/ 100.0f; /* cm to m */
+ float si_units = (distance * 1.0f) / 100.0f; /* cm to m */
struct range_finder_report report;
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
report.timestamp = hrt_absolute_time();
- report.error_count = perf_event_count(_comms_errors);
+ report.error_count = perf_event_count(_comms_errors);
report.distance = si_units;
report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
-
+
/* publish it */
orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
@@ -519,17 +530,19 @@ MB12XX::start()
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&MB12XX::cycle_trampoline, this, 1);
-
+
/* notify about state change */
struct subsystem_info_s info = {
true,
true,
true,
- SUBSYSTEM_TYPE_RANGEFINDER};
+ SUBSYSTEM_TYPE_RANGEFINDER
+ };
static orb_advert_t pub = -1;
if (pub > 0) {
orb_publish(ORB_ID(subsystem_info), pub, &info);
+
} else {
pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
@@ -583,8 +596,9 @@ MB12XX::cycle()
}
/* measurement phase */
- if (OK != measure())
+ if (OK != measure()) {
log("measure error");
+ }
/* next phase is collection */
_collect_phase = true;
@@ -635,33 +649,37 @@ start()
{
int fd;
- if (g_dev != nullptr)
+ if (g_dev != nullptr) {
errx(1, "already started");
+ }
/* create the driver */
g_dev = new MB12XX(MB12XX_BUS);
- if (g_dev == nullptr)
+ if (g_dev == nullptr) {
goto fail;
+ }
- if (OK != g_dev->init())
+ if (OK != g_dev->init()) {
goto fail;
+ }
/* set the poll rate to default, starts automatic data collection */
fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
goto fail;
+ }
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
goto fail;
+ }
exit(0);
fail:
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
}
@@ -674,15 +692,14 @@ fail:
*/
void stop()
{
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
- }
- else
- {
+
+ } else {
errx(1, "driver not running");
}
+
exit(0);
}
@@ -700,22 +717,25 @@ test()
int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
err(1, "%s open failed (try 'mb12xx start' if the driver is not running", RANGE_FINDER_DEVICE_PATH);
+ }
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
- if (sz != sizeof(report))
+ if (sz != sizeof(report)) {
err(1, "immediate read failed");
+ }
warnx("single read");
warnx("measurement: %0.2f m", (double)report.distance);
warnx("time: %lld", report.timestamp);
/* start the sensor polling at 2Hz */
- if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
errx(1, "failed to set 2Hz poll rate");
+ }
/* read the sensor 5x and report each value */
for (unsigned i = 0; i < 5; i++) {
@@ -726,20 +746,27 @@ test()
fds.events = POLLIN;
ret = poll(&fds, 1, 2000);
- if (ret != 1)
+ if (ret != 1) {
errx(1, "timed out waiting for sensor data");
+ }
/* now go get it */
sz = read(fd, &report, sizeof(report));
- if (sz != sizeof(report))
+ if (sz != sizeof(report)) {
err(1, "periodic read failed");
+ }
warnx("periodic read %u", i);
warnx("measurement: %0.3f", (double)report.distance);
warnx("time: %lld", report.timestamp);
}
+ /* reset the sensor polling to default rate */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
+ errx(1, "failed to set default poll rate");
+ }
+
errx(0, "PASS");
}
@@ -751,14 +778,17 @@ reset()
{
int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
err(1, "failed ");
+ }
- if (ioctl(fd, SENSORIOCRESET, 0) < 0)
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
err(1, "driver reset failed");
+ }
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
err(1, "driver poll restart failed");
+ }
exit(0);
}
@@ -769,8 +799,9 @@ reset()
void
info()
{
- if (g_dev == nullptr)
+ if (g_dev == nullptr) {
errx(1, "driver not running");
+ }
printf("state @ %p\n", g_dev);
g_dev->print_info();
@@ -786,32 +817,37 @@ mb12xx_main(int argc, char *argv[])
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
+ if (!strcmp(argv[1], "start")) {
mb12xx::start();
-
- /*
- * Stop the driver
- */
- if (!strcmp(argv[1], "stop"))
- mb12xx::stop();
+ }
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop")) {
+ mb12xx::stop();
+ }
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
+ if (!strcmp(argv[1], "test")) {
mb12xx::test();
+ }
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
+ if (!strcmp(argv[1], "reset")) {
mb12xx::reset();
+ }
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
+ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
mb12xx::info();
+ }
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
}
diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp
index d43e3aef9e..5d1f58b854 100644
--- a/src/drivers/md25/md25.cpp
+++ b/src/drivers/md25/md25.cpp
@@ -52,7 +52,7 @@
#include
#include
-#include
+#include
#include
#include
@@ -587,7 +587,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitu
float prev_revolution = md25.getRevolutions1();
// debug publication
- control::UOrbPublication debug_msg(NULL,
+ uORB::Publication debug_msg(NULL,
ORB_ID(debug_key_value));
// sine wave for motor 1
diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp
index 1661f67f9a..962c6b881d 100644
--- a/src/drivers/md25/md25.hpp
+++ b/src/drivers/md25/md25.hpp
@@ -46,7 +46,7 @@
#include
#include
-#include
+#include
#include
#include
@@ -270,7 +270,7 @@ private:
struct pollfd _controlPoll;
/** actuator controls subscription */
- control::UOrbSubscription _actuators;
+ uORB::Subscription _actuators;
// local copy of data from i2c device
uint8_t _version;
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
index 06d89abf77..c0f3c28e0f 100644
--- a/src/drivers/meas_airspeed/meas_airspeed.cpp
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -79,12 +79,15 @@
#include
#include
+#include
+
#include
#include
#include
#include
#include
+#include
#include
@@ -99,12 +102,14 @@
#define ADDR_READ_MR 0x00 /* write to this address to start conversion */
/* Measurement rate is 100Hz */
+#define MEAS_RATE 100.0f
+#define MEAS_DRIVER_FILTER_FREQ 3.0f
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
class MEASAirspeed : public Airspeed
{
public:
- MEASAirspeed(int bus, int address = I2C_ADDRESS_MS4525DO, const char* path = PATH_MS4525);
+ MEASAirspeed(int bus, int address = I2C_ADDRESS_MS4525DO, const char *path = PATH_MS4525);
protected:
@@ -116,6 +121,15 @@ protected:
virtual int measure();
virtual int collect();
+ math::LowPassFilter2p _filter;
+
+ /**
+ * Correct for 5V rail voltage variations
+ */
+ void voltage_correction(float &diff_pres_pa, float &temperature);
+
+ int _t_system_power;
+ struct system_power_s system_power;
};
/*
@@ -123,10 +137,12 @@ protected:
*/
extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]);
-MEASAirspeed::MEASAirspeed(int bus, int address, const char* path) : Airspeed(bus, address,
- CONVERSION_INTERVAL, path)
+MEASAirspeed::MEASAirspeed(int bus, int address, const char *path) : Airspeed(bus, address,
+ CONVERSION_INTERVAL, path),
+ _filter(MEAS_RATE, MEAS_DRIVER_FILTER_FREQ),
+ _t_system_power(-1)
{
-
+ memset(&system_power, 0, sizeof(system_power));
}
int
@@ -161,23 +177,25 @@ MEASAirspeed::collect()
ret = transfer(nullptr, 0, &val[0], 4);
if (ret < 0) {
- perf_count(_comms_errors);
- perf_end(_sample_perf);
+ perf_count(_comms_errors);
+ perf_end(_sample_perf);
return ret;
}
- uint8_t status = val[0] & 0xC0;
+ uint8_t status = (val[0] & 0xC0) >> 6;
- if (status == 2) {
- log("err: stale data");
- perf_count(_comms_errors);
- perf_end(_sample_perf);
- return ret;
- } else if (status == 3) {
- log("err: fault");
- perf_count(_comms_errors);
- perf_end(_sample_perf);
- return ret;
+ switch (status) {
+ case 0:
+ break;
+
+ case 1:
+ /* fallthrough */
+ case 2:
+ /* fallthrough */
+ case 3:
+ perf_count(_comms_errors);
+ perf_end(_sample_perf);
+ return -EAGAIN;
}
int16_t dp_raw = 0, dT_raw = 0;
@@ -186,28 +204,67 @@ MEASAirspeed::collect()
dp_raw = 0x3FFF & dp_raw;
dT_raw = (val[2] << 8) + val[3];
dT_raw = (0xFFE0 & dT_raw) >> 5;
- float temperature = ((200 * dT_raw) / 2047) - 50;
+ float temperature = ((200.0f * dT_raw) / 2047) - 50;
- /* calculate differential pressure. As its centered around 8000
- * and can go positive or negative, enforce absolute value
- */
+ // Calculate differential pressure. As its centered around 8000
+ // and can go positive or negative
const float P_min = -1.0f;
const float P_max = 1.0f;
- float diff_press_pa = fabsf( ( ((float)dp_raw - 0.1f*16383.0f) * (P_max-P_min)/(0.8f*16383.0f) + P_min) * 6894.8f) - _diff_pres_offset;
- if (diff_press_pa < 0.0f)
- diff_press_pa = 0.0f;
+ const float PSI_to_Pa = 6894.757f;
+ /*
+ this equation is an inversion of the equation in the
+ pressure transfer function figure on page 4 of the datasheet
+ We negate the result so that positive differential pressures
+ are generated when the bottom port is used as the static
+ port on the pitot and top port is used as the dynamic port
+ */
+ float diff_press_PSI = -((dp_raw - 0.1f*16383) * (P_max-P_min)/(0.8f*16383) + P_min);
+ float diff_press_pa_raw = diff_press_PSI * PSI_to_Pa;
+
+ // correct for 5V rail voltage if possible
+ voltage_correction(diff_press_pa_raw, temperature);
+
+ float diff_press_pa = fabsf(diff_press_pa_raw - _diff_pres_offset);
+
+ /*
+ note that we return both the absolute value with offset
+ applied and a raw value without the offset applied. This
+ makes it possible for higher level code to detect if the
+ user has the tubes connected backwards, and also makes it
+ possible to correctly use offsets calculated by a higher
+ level airspeed driver.
+
+ With the above calculation the MS4525 sensor will produce a
+ positive number when the top port is used as a dynamic port
+ and bottom port is used as the static port
+
+ Also note that the _diff_pres_offset is applied before the
+ fabsf() not afterwards. It needs to be done this way to
+ prevent a bias at low speeds, but this also means that when
+ setting a offset you must set it based on the raw value, not
+ the offset value
+ */
+
struct differential_pressure_s report;
/* track maximum differential pressure measured (so we can work out top speed). */
if (diff_press_pa > _max_differential_pressure_pa) {
- _max_differential_pressure_pa = diff_press_pa;
+ _max_differential_pressure_pa = diff_press_pa;
}
report.timestamp = hrt_absolute_time();
- report.error_count = perf_event_count(_comms_errors);
+ report.error_count = perf_event_count(_comms_errors);
report.temperature = temperature;
report.differential_pressure_pa = diff_press_pa;
+ report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa);
+
+ /* the dynamics of the filter can make it overshoot into the negative range */
+ if (report.differential_pressure_filtered_pa < 0.0f) {
+ report.differential_pressure_filtered_pa = _filter.reset(diff_press_pa);
+ }
+
+ report.differential_pressure_raw_pa = diff_press_pa_raw;
report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
@@ -231,13 +288,17 @@ MEASAirspeed::collect()
void
MEASAirspeed::cycle()
{
+ int ret;
+
/* collection phase? */
if (_collect_phase) {
/* perform collection */
- if (OK != collect()) {
+ ret = collect();
+ if (OK != ret) {
/* restart the measurement state machine */
start();
+ _sensor_ok = false;
return;
}
@@ -261,8 +322,12 @@ MEASAirspeed::cycle()
}
/* measurement phase */
- if (OK != measure())
- log("measure error");
+ ret = measure();
+ if (OK != ret) {
+ debug("measure error");
+ }
+
+ _sensor_ok = (ret == OK);
/* next phase is collection */
_collect_phase = true;
@@ -275,6 +340,62 @@ MEASAirspeed::cycle()
USEC2TICK(CONVERSION_INTERVAL));
}
+/**
+ correct for 5V rail voltage if the system_power ORB topic is
+ available
+
+ See http://uav.tridgell.net/MS4525/MS4525-offset.png for a graph of
+ offset versus voltage for 3 sensors
+ */
+void
+MEASAirspeed::voltage_correction(float &diff_press_pa, float &temperature)
+{
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ if (_t_system_power == -1) {
+ _t_system_power = orb_subscribe(ORB_ID(system_power));
+ }
+ if (_t_system_power == -1) {
+ // not available
+ return;
+ }
+ bool updated = false;
+ orb_check(_t_system_power, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(system_power), _t_system_power, &system_power);
+ }
+ if (system_power.voltage5V_v < 3.0f || system_power.voltage5V_v > 6.0f) {
+ // not valid, skip correction
+ return;
+ }
+
+ const float slope = 65.0f;
+ /*
+ apply a piecewise linear correction, flattening at 0.5V from 5V
+ */
+ float voltage_diff = system_power.voltage5V_v - 5.0f;
+ if (voltage_diff > 0.5f) {
+ voltage_diff = 0.5f;
+ }
+ if (voltage_diff < -0.5f) {
+ voltage_diff = -0.5f;
+ }
+ diff_press_pa -= voltage_diff * slope;
+
+ /*
+ the temperature masurement varies as well
+ */
+ const float temp_slope = 0.887f;
+ voltage_diff = system_power.voltage5V_v - 5.0f;
+ if (voltage_diff > 0.5f) {
+ voltage_diff = 0.5f;
+ }
+ if (voltage_diff < -1.0f) {
+ voltage_diff = -1.0f;
+ }
+ temperature -= voltage_diff * temp_slope;
+#endif // CONFIG_ARCH_BOARD_PX4FMU_V2
+}
+
/**
* Local functions in support of the shell command.
*/
@@ -303,15 +424,17 @@ start(int i2c_bus)
{
int fd;
- if (g_dev != nullptr)
+ if (g_dev != nullptr) {
errx(1, "already started");
+ }
/* create the driver, try the MS4525DO first */
g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO, PATH_MS4525);
/* check if the MS4525DO was instantiated */
- if (g_dev == nullptr)
+ if (g_dev == nullptr) {
goto fail;
+ }
/* try the MS5525DSO next if init fails */
if (OK != g_dev->Airspeed::init()) {
@@ -319,22 +442,26 @@ start(int i2c_bus)
g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO, PATH_MS5525);
/* check if the MS5525DSO was instantiated */
- if (g_dev == nullptr)
+ if (g_dev == nullptr) {
goto fail;
+ }
/* both versions failed if the init for the MS5525DSO fails, give up */
- if (OK != g_dev->Airspeed::init())
+ if (OK != g_dev->Airspeed::init()) {
goto fail;
+ }
}
/* set the poll rate to default, starts automatic data collection */
fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
goto fail;
+ }
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
goto fail;
+ }
exit(0);
@@ -345,7 +472,7 @@ fail:
g_dev = nullptr;
}
- errx(1, "driver start failed");
+ errx(1, "no MS4525 airspeed sensor connected");
}
/**
@@ -379,21 +506,24 @@ test()
int fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
err(1, "%s open failed (try 'meas_airspeed start' if the driver is not running", AIRSPEED_DEVICE_PATH);
+ }
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
- if (sz != sizeof(report))
+ if (sz != sizeof(report)) {
err(1, "immediate read failed");
+ }
warnx("single read");
- warnx("diff pressure: %8.4f pa", (double)report.differential_pressure_pa);
+ warnx("diff pressure: %d pa", (int)report.differential_pressure_pa);
/* start the sensor polling at 2Hz */
- if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
errx(1, "failed to set 2Hz poll rate");
+ }
/* read the sensor 5x and report each value */
for (unsigned i = 0; i < 5; i++) {
@@ -404,23 +534,26 @@ test()
fds.events = POLLIN;
ret = poll(&fds, 1, 2000);
- if (ret != 1)
+ if (ret != 1) {
errx(1, "timed out waiting for sensor data");
+ }
/* now go get it */
sz = read(fd, &report, sizeof(report));
- if (sz != sizeof(report))
+ if (sz != sizeof(report)) {
err(1, "periodic read failed");
+ }
warnx("periodic read %u", i);
- warnx("diff pressure: %8.4f pa", (double)report.differential_pressure_pa);
+ warnx("diff pressure: %d pa", (int)report.differential_pressure_pa);
warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature);
}
/* reset the sensor polling to its default rate */
- if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT))
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
errx(1, "failed to set default rate");
+ }
errx(0, "PASS");
}
@@ -433,14 +566,17 @@ reset()
{
int fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
err(1, "failed ");
+ }
- if (ioctl(fd, SENSORIOCRESET, 0) < 0)
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
err(1, "driver reset failed");
+ }
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
err(1, "driver poll restart failed");
+ }
exit(0);
}
@@ -451,8 +587,9 @@ reset()
void
info()
{
- if (g_dev == nullptr)
+ if (g_dev == nullptr) {
errx(1, "driver not running");
+ }
printf("state @ %p\n", g_dev);
g_dev->print_info();
@@ -491,32 +628,37 @@ meas_airspeed_main(int argc, char *argv[])
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
+ if (!strcmp(argv[1], "start")) {
meas_airspeed::start(i2c_bus);
+ }
/*
* Stop the driver
*/
- if (!strcmp(argv[1], "stop"))
+ if (!strcmp(argv[1], "stop")) {
meas_airspeed::stop();
+ }
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
+ if (!strcmp(argv[1], "test")) {
meas_airspeed::test();
+ }
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
+ if (!strcmp(argv[1], "reset")) {
meas_airspeed::reset();
+ }
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
+ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
meas_airspeed::info();
+ }
meas_airspeed_usage();
exit(0);
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index 705e98eea4..5954c40da0 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -92,8 +92,20 @@
#define MOTOR_SPINUP_COUNTER 30
#define ESC_UORB_PUBLISH_DELAY 500000
-
-
+struct MotorData_t {
+ unsigned int Version; // the version of the BL (0 = old)
+ unsigned int SetPoint; // written by attitude controller
+ unsigned int SetPointLowerBits; // for higher Resolution of new BLs
+ float SetPoint_PX4; // Values from PX4
+ unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
+ unsigned int ReadMode; // select data to read
+ unsigned short RawPwmValue; // length of PWM pulse
+ // the following bytes must be exactly in that order!
+ unsigned int Current; // in 0.1 A steps, read back from BL
+ unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit
+ unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in
+ unsigned int RoundCount;
+};
class MK : public device::I2C
{
@@ -154,8 +166,10 @@ private:
actuator_controls_s _controls;
+ MotorData_t Motor[MAX_MOTORS];
+
static void task_main_trampoline(int argc, char *argv[]);
- void task_main() __attribute__((noreturn));
+ void task_main();
static int control_callback(uintptr_t handle,
uint8_t control_group,
@@ -195,24 +209,6 @@ const int blctrlAddr_px4[] = { 0, 0, 0, 0, 0, 0, 0, 0};
int addrTranslator[] = {0, 0, 0, 0, 0, 0, 0, 0};
-struct MotorData_t {
- unsigned int Version; // the version of the BL (0 = old)
- unsigned int SetPoint; // written by attitude controller
- unsigned int SetPointLowerBits; // for higher Resolution of new BLs
- float SetPoint_PX4; // Values from PX4
- unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
- unsigned int ReadMode; // select data to read
- unsigned short RawPwmValue; // length of PWM pulse
- // the following bytes must be exactly in that order!
- unsigned int Current; // in 0.1 A steps, read back from BL
- unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit
- unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in
- unsigned int RoundCount;
-};
-
-MotorData_t Motor[MAX_MOTORS];
-
-
namespace
{
@@ -1015,7 +1011,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_GET(0) ... PWM_SERVO_GET(_max_actuators - 1):
/* copy the current output value from the channel */
- *(servo_position_t *)arg = Motor[cmd - PWM_SERVO_SET(0)].RawPwmValue;
+ *(servo_position_t *)arg = Motor[cmd - PWM_SERVO_GET(0)].RawPwmValue;
break;
diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 0ef056273f..3fe1b0abcb 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -526,6 +526,7 @@ void
MS5611::cycle()
{
int ret;
+ unsigned dummy;
/* collection phase? */
if (_collect_phase) {
@@ -542,6 +543,8 @@ MS5611::cycle()
} else {
//log("collection error %d", ret);
}
+ /* issue a reset command to the sensor */
+ _interface->ioctl(IOCTL_RESET, dummy);
/* reset the collection state machine and try again */
start_cycle();
return;
@@ -573,6 +576,8 @@ MS5611::cycle()
ret = measure();
if (ret != OK) {
//log("measure error %d", ret);
+ /* issue a reset command to the sensor */
+ _interface->ioctl(IOCTL_RESET, dummy);
/* reset the collection state machine and try again */
start_cycle();
return;
diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp
index 26216e840f..8759d16a16 100644
--- a/src/drivers/ms5611/ms5611_spi.cpp
+++ b/src/drivers/ms5611/ms5611_spi.cpp
@@ -117,7 +117,7 @@ private:
device::Device *
MS5611_spi_interface(ms5611::prom_u &prom_buf)
{
- return new MS5611_SPI(1 /* XXX MAGIC NUMBER */, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
+ return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
}
MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) :
diff --git a/src/modules/fixedwing_pos_control/module.mk b/src/drivers/px4flow/module.mk
similarity index 89%
rename from src/modules/fixedwing_pos_control/module.mk
rename to src/drivers/px4flow/module.mk
index b976377e93..d3062e4579 100644
--- a/src/modules/fixedwing_pos_control/module.mk
+++ b/src/drivers/px4flow/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+# Copyright (c) 2013 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -32,9 +32,9 @@
############################################################################
#
-# Fixedwing PositionControl application
+# Makefile to build the PX4FLOW driver.
#
-MODULE_COMMAND = fixedwing_pos_control
+MODULE_COMMAND = px4flow
-SRCS = fixedwing_pos_control_main.c
+SRCS = px4flow.cpp
diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp
new file mode 100644
index 0000000000..f214b5964f
--- /dev/null
+++ b/src/drivers/px4flow/px4flow.cpp
@@ -0,0 +1,806 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4flow.cpp
+ * @author Dominik Honegger
+ *
+ * Driver for the PX4FLOW module connected via I2C.
+ */
+
+#include
+
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+//#include
+
+#include
+
+/* Configuration Constants */
+#define PX4FLOW_BUS PX4_I2C_BUS_EXPANSION
+#define I2C_FLOW_ADDRESS 0x42 //* 7-bit address. 8-bit address is 0x84
+//range 0x42 - 0x49
+
+/* PX4FLOW Registers addresses */
+#define PX4FLOW_REG 0x00 /* Measure Register */
+
+#define PX4FLOW_CONVERSION_INTERVAL 8000 /* 8ms 125Hz
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error This requires CONFIG_SCHED_WORKQUEUE.
+#endif
+
+//struct i2c_frame
+//{
+// uint16_t frame_count;
+// int16_t pixel_flow_x_sum;
+// int16_t pixel_flow_y_sum;
+// int16_t flow_comp_m_x;
+// int16_t flow_comp_m_y;
+// int16_t qual;
+// int16_t gyro_x_rate;
+// int16_t gyro_y_rate;
+// int16_t gyro_z_rate;
+// uint8_t gyro_range;
+// uint8_t sonar_timestamp;
+// int16_t ground_distance;
+//};
+//
+//struct i2c_frame f;
+
+class PX4FLOW : public device::I2C
+{
+public:
+ PX4FLOW(int bus = PX4FLOW_BUS, int address = I2C_FLOW_ADDRESS);
+ virtual ~PX4FLOW();
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ /**
+ * Diagnostics - print some basic information about the driver.
+ */
+ void print_info();
+
+protected:
+ virtual int probe();
+
+private:
+
+ work_s _work;
+ RingBuffer *_reports;
+ bool _sensor_ok;
+ int _measure_ticks;
+ bool _collect_phase;
+
+ orb_advert_t _px4flow_topic;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+ perf_counter_t _buffer_overflows;
+
+ /**
+ * Test whether the device supported by the driver is present at a
+ * specific address.
+ *
+ * @param address The I2C bus address to probe.
+ * @return True if the device is present.
+ */
+ int probe_address(uint8_t address);
+
+ /**
+ * Initialise the automatic measurement state machine and start it.
+ *
+ * @note This function is called at open and error time. It might make sense
+ * to make it more aggressive about resetting the bus in case of errors.
+ */
+ void start();
+
+ /**
+ * Stop the automatic measurement state machine.
+ */
+ void stop();
+
+ /**
+ * Perform a poll cycle; collect from the previous measurement
+ * and start a new one.
+ */
+ void cycle();
+ int measure();
+ int collect();
+ /**
+ * Static trampoline from the workq context; because we don't have a
+ * generic workq wrapper yet.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void cycle_trampoline(void *arg);
+
+
+};
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int px4flow_main(int argc, char *argv[]);
+
+PX4FLOW::PX4FLOW(int bus, int address) :
+ I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, 400000),//400khz
+ _reports(nullptr),
+ _sensor_ok(false),
+ _measure_ticks(0),
+ _collect_phase(false),
+ _px4flow_topic(-1),
+ _sample_perf(perf_alloc(PC_ELAPSED, "px4flow_read")),
+ _comms_errors(perf_alloc(PC_COUNT, "px4flow_comms_errors")),
+ _buffer_overflows(perf_alloc(PC_COUNT, "px4flow_buffer_overflows"))
+{
+ // enable debug() calls
+ _debug_enabled = true;
+
+ // work_cancel in the dtor will explode if we don't do this...
+ memset(&_work, 0, sizeof(_work));
+}
+
+PX4FLOW::~PX4FLOW()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ /* free any existing reports */
+ if (_reports != nullptr)
+ delete _reports;
+}
+
+int
+PX4FLOW::init()
+{
+ int ret = ERROR;
+
+ /* do I2C init (and probe) first */
+ if (I2C::init() != OK)
+ goto out;
+
+ /* allocate basic report buffers */
+ _reports = new RingBuffer(2, sizeof(px4flow_report));
+
+ if (_reports == nullptr)
+ goto out;
+
+ /* get a publish handle on the px4flow topic */
+ struct px4flow_report zero_report;
+ memset(&zero_report, 0, sizeof(zero_report));
+ _px4flow_topic = orb_advertise(ORB_ID(optical_flow), &zero_report);
+
+ if (_px4flow_topic < 0)
+ debug("failed to create px4flow object. Did you start uOrb?");
+
+ ret = OK;
+ /* sensor is ok, but we don't really know if it is within range */
+ _sensor_ok = true;
+out:
+ return ret;
+}
+
+int
+PX4FLOW::probe()
+{
+ return measure();
+}
+
+int
+PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case SENSORIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _measure_ticks = 0;
+ return OK;
+
+ /* external signalling (DRDY) not supported */
+ case SENSOR_POLLRATE_EXTERNAL:
+
+ /* zero would be bad */
+ case 0:
+ return -EINVAL;
+
+ /* set default/max polling rate */
+ case SENSOR_POLLRATE_MAX:
+ case SENSOR_POLLRATE_DEFAULT: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* set interval for next measurement to minimum legal value */
+ _measure_ticks = USEC2TICK(PX4FLOW_CONVERSION_INTERVAL);
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
+
+ return OK;
+ }
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* convert hz to tick interval via microseconds */
+ unsigned ticks = USEC2TICK(1000000 / arg);
+
+ /* check against maximum rate */
+ if (ticks < USEC2TICK(PX4FLOW_CONVERSION_INTERVAL))
+ return -EINVAL;
+
+ /* update interval for next measurement */
+ _measure_ticks = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
+
+ return OK;
+ }
+ }
+ }
+
+ case SENSORIOCGPOLLRATE:
+ if (_measure_ticks == 0)
+ return SENSOR_POLLRATE_MANUAL;
+
+ return (1000 / _measure_ticks);
+
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100))
+ return -EINVAL;
+
+ irqstate_t flags = irqsave();
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+ irqrestore(flags);
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _reports->size();
+
+ case SENSORIOCRESET:
+ /* XXX implement this */
+ return -EINVAL;
+
+ default:
+ /* give it to the superclass */
+ return I2C::ioctl(filp, cmd, arg);
+ }
+}
+
+ssize_t
+PX4FLOW::read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct px4flow_report);
+ struct px4flow_report *rbuf = reinterpret_cast(buffer);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1)
+ return -ENOSPC;
+
+ /* if automatic measurement is enabled */
+ if (_measure_ticks > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ * Note that we may be pre-empted by the workq thread while we are doing this;
+ * we are careful to avoid racing with them.
+ */
+ while (count--) {
+ if (_reports->get(rbuf)) {
+ ret += sizeof(*rbuf);
+ rbuf++;
+ }
+ }
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement - run one conversion */
+ do {
+ _reports->flush();
+
+ /* trigger a measurement */
+ if (OK != measure()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* wait for it to complete */
+ usleep(PX4FLOW_CONVERSION_INTERVAL);
+
+ /* run the collection phase */
+ if (OK != collect()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* state machine will have generated a report, copy it out */
+ if (_reports->get(rbuf)) {
+ ret = sizeof(*rbuf);
+ }
+
+ } while (0);
+
+ return ret;
+}
+
+int
+PX4FLOW::measure()
+{
+ int ret;
+
+ /*
+ * Send the command to begin a measurement.
+ */
+ uint8_t cmd = PX4FLOW_REG;
+ ret = transfer(&cmd, 1, nullptr, 0);
+
+ if (OK != ret)
+ {
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+ printf("i2c::transfer flow returned %d");
+ return ret;
+ }
+ ret = OK;
+
+ return ret;
+}
+
+int
+PX4FLOW::collect()
+{
+ int ret = -EIO;
+
+ /* read from the sensor */
+ uint8_t val[22] = {0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0};
+
+ perf_begin(_sample_perf);
+
+ ret = transfer(nullptr, 0, &val[0], 22);
+
+ if (ret < 0)
+ {
+ log("error reading from sensor: %d", ret);
+ perf_count(_comms_errors);
+ perf_end(_sample_perf);
+ return ret;
+ }
+
+// f.frame_count = val[1] << 8 | val[0];
+// f.pixel_flow_x_sum= val[3] << 8 | val[2];
+// f.pixel_flow_y_sum= val[5] << 8 | val[4];
+// f.flow_comp_m_x= val[7] << 8 | val[6];
+// f.flow_comp_m_y= val[9] << 8 | val[8];
+// f.qual= val[11] << 8 | val[10];
+// f.gyro_x_rate= val[13] << 8 | val[12];
+// f.gyro_y_rate= val[15] << 8 | val[14];
+// f.gyro_z_rate= val[17] << 8 | val[16];
+// f.gyro_range= val[18];
+// f.sonar_timestamp= val[19];
+// f.ground_distance= val[21] << 8 | val[20];
+
+ int16_t flowcx = val[7] << 8 | val[6];
+ int16_t flowcy = val[9] << 8 | val[8];
+ int16_t gdist = val[21] << 8 | val[20];
+
+ struct px4flow_report report;
+ report.flow_comp_x_m = float(flowcx)/1000.0f;
+ report.flow_comp_y_m = float(flowcy)/1000.0f;
+ report.flow_raw_x= val[3] << 8 | val[2];
+ report.flow_raw_y= val[5] << 8 | val[4];
+ report.ground_distance_m =float(gdist)/1000.0f;
+ report.quality= val[10];
+ report.sensor_id = 0;
+ report.timestamp = hrt_absolute_time();
+
+
+ /* publish it */
+ orb_publish(ORB_ID(optical_flow), _px4flow_topic, &report);
+
+ /* post a report to the ring */
+ if (_reports->force(&report)) {
+ perf_count(_buffer_overflows);
+ }
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ ret = OK;
+
+ perf_end(_sample_perf);
+ return ret;
+}
+
+void
+PX4FLOW::start()
+{
+ /* reset the report ring and state machine */
+ _collect_phase = false;
+ _reports->flush();
+
+ /* schedule a cycle to start things */
+ work_queue(HPWORK, &_work, (worker_t)&PX4FLOW::cycle_trampoline, this, 1);
+
+ /* notify about state change */
+ struct subsystem_info_s info = {
+ true,
+ true,
+ true,
+ SUBSYSTEM_TYPE_OPTICALFLOW};
+ static orb_advert_t pub = -1;
+
+ if (pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), pub, &info);
+ } else {
+ pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ }
+}
+
+void
+PX4FLOW::stop()
+{
+ work_cancel(HPWORK, &_work);
+}
+
+void
+PX4FLOW::cycle_trampoline(void *arg)
+{
+ PX4FLOW *dev = (PX4FLOW *)arg;
+
+ dev->cycle();
+}
+
+void
+PX4FLOW::cycle()
+{
+ /* collection phase? */
+ if (_collect_phase) {
+
+ /* perform collection */
+ if (OK != collect()) {
+ log("collection error");
+ /* restart the measurement state machine */
+ start();
+ return;
+ }
+
+ /* next phase is measurement */
+ _collect_phase = false;
+
+ /*
+ * Is there a collect->measure gap?
+ */
+ if (_measure_ticks > USEC2TICK(PX4FLOW_CONVERSION_INTERVAL)) {
+
+ /* schedule a fresh cycle call when we are ready to measure again */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&PX4FLOW::cycle_trampoline,
+ this,
+ _measure_ticks - USEC2TICK(PX4FLOW_CONVERSION_INTERVAL));
+
+ return;
+ }
+ }
+
+ /* measurement phase */
+ if (OK != measure())
+ log("measure error");
+
+ /* next phase is collection */
+ _collect_phase = true;
+
+ /* schedule a fresh cycle call when the measurement is done */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&PX4FLOW::cycle_trampoline,
+ this,
+ USEC2TICK(PX4FLOW_CONVERSION_INTERVAL));
+}
+
+void
+PX4FLOW::print_info()
+{
+ perf_print_counter(_sample_perf);
+ perf_print_counter(_comms_errors);
+ perf_print_counter(_buffer_overflows);
+ printf("poll interval: %u ticks\n", _measure_ticks);
+ _reports->print_info("report queue");
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace px4flow
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+const int ERROR = -1;
+
+PX4FLOW *g_dev;
+
+void start();
+void stop();
+void test();
+void reset();
+void info();
+
+/**
+ * Start the driver.
+ */
+void
+start()
+{
+ int fd;
+
+ if (g_dev != nullptr)
+ errx(1, "already started");
+
+ /* create the driver */
+ g_dev = new PX4FLOW(PX4FLOW_BUS);
+
+ if (g_dev == nullptr)
+ goto fail;
+
+ if (OK != g_dev->init())
+ goto fail;
+
+ /* set the poll rate to default, starts automatic data collection */
+ fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0)
+ goto fail;
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX) < 0)
+ goto fail;
+
+ exit(0);
+
+fail:
+
+ if (g_dev != nullptr)
+ {
+ delete g_dev;
+ g_dev = nullptr;
+ }
+
+ errx(1, "driver start failed");
+}
+
+/**
+ * Stop the driver
+ */
+void stop()
+{
+ if (g_dev != nullptr)
+ {
+ delete g_dev;
+ g_dev = nullptr;
+ }
+ else
+ {
+ errx(1, "driver not running");
+ }
+ exit(0);
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ */
+void
+test()
+{
+ struct px4flow_report report;
+ ssize_t sz;
+ int ret;
+
+ int fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0)
+ err(1, "%s open failed (try 'px4flow start' if the driver is not running", PX4FLOW_DEVICE_PATH);
+
+ /* do a simple demand read */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report))
+ // err(1, "immediate read failed");
+
+ warnx("single read");
+ warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
+ warnx("flowy: %0.2f m/s", (double)report.flow_comp_y_m);
+ warnx("time: %lld", report.timestamp);
+
+
+ /* start the sensor polling at 2Hz */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
+ errx(1, "failed to set 2Hz poll rate");
+
+ /* read the sensor 5x and report each value */
+ for (unsigned i = 0; i < 5; i++) {
+ struct pollfd fds;
+
+ /* wait for data to be ready */
+ fds.fd = fd;
+ fds.events = POLLIN;
+ ret = poll(&fds, 1, 2000);
+
+ if (ret != 1)
+ errx(1, "timed out waiting for sensor data");
+
+ /* now go get it */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report))
+ err(1, "periodic read failed");
+
+ warnx("periodic read %u", i);
+ warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
+ warnx("flowy: %0.2f m/s", (double)report.flow_comp_y_m);
+ warnx("time: %lld", report.timestamp);
+
+
+ }
+
+ errx(0, "PASS");
+}
+
+/**
+ * Reset the driver.
+ */
+void
+reset()
+{
+ int fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0)
+ err(1, "failed ");
+
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0)
+ err(1, "driver reset failed");
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ err(1, "driver poll restart failed");
+
+ exit(0);
+}
+
+/**
+ * Print a little info about the driver.
+ */
+void
+info()
+{
+ if (g_dev == nullptr)
+ errx(1, "driver not running");
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ exit(0);
+}
+
+} // namespace
+
+int
+px4flow_main(int argc, char *argv[])
+{
+ /*
+ * Start/load the driver.
+ */
+ if (!strcmp(argv[1], "start"))
+ px4flow::start();
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop"))
+ px4flow::stop();
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test"))
+ px4flow::test();
+
+ /*
+ * Reset the driver.
+ */
+ if (!strcmp(argv[1], "reset"))
+ px4flow::reset();
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
+ px4flow::info();
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
+}
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index a70ff6c5c5..fd69cf795b 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -92,6 +92,7 @@ public:
MODE_2PWM,
MODE_4PWM,
MODE_6PWM,
+ MODE_8PWM,
};
PX4FMU();
virtual ~PX4FMU();
@@ -113,6 +114,9 @@ private:
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
static const unsigned _max_actuators = 6;
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ static const unsigned _max_actuators = 8;
+#endif
Mode _mode;
unsigned _pwm_default_rate;
@@ -120,19 +124,25 @@ private:
uint32_t _pwm_alt_rate_channels;
unsigned _current_update_rate;
int _task;
- int _t_actuators;
- int _t_actuator_armed;
- orb_advert_t _t_outputs;
+ int _armed_sub;
+ orb_advert_t _outputs_pub;
+ actuator_armed_s _armed;
unsigned _num_outputs;
bool _primary_pwm_device;
volatile bool _task_should_exit;
- bool _armed;
+ bool _servo_armed;
bool _pwm_on;
MixerGroup *_mixers;
- actuator_controls_s _controls;
+ uint32_t _groups_required;
+ uint32_t _groups_subscribed;
+ int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS];
+ actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS];
+ orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS];
+ pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS];
+ unsigned _poll_fds_num;
pwm_limit_t _pwm_limit;
uint16_t _failsafe_pwm[_max_actuators];
@@ -143,13 +153,13 @@ private:
unsigned _num_disarmed_set;
static void task_main_trampoline(int argc, char *argv[]);
- void task_main() __attribute__((noreturn));
+ void task_main();
static int control_callback(uintptr_t handle,
uint8_t control_group,
uint8_t control_index,
float &input);
-
+ void subscribe();
int set_pwm_rate(unsigned rate_map, unsigned default_rate, unsigned alt_rate);
int pwm_ioctl(file *filp, int cmd, unsigned long arg);
@@ -197,6 +207,20 @@ const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
{GPIO_VDD_5V_HIPOWER_OC, 0, 0},
{GPIO_VDD_5V_PERIPH_OC, 0, 0},
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ /* AeroCore breaks out User GPIOs on J11 */
+ {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
+ {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
+ {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0},
+ {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0},
+ {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0},
+ {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, 0},
+ {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, 0},
+ {GPIO_GPIO8_INPUT, GPIO_GPIO8_OUTPUT, 0},
+ {GPIO_GPIO9_INPUT, GPIO_GPIO9_OUTPUT, 0},
+ {GPIO_GPIO10_INPUT, GPIO_GPIO10_OUTPUT, 0},
+ {GPIO_GPIO11_INPUT, GPIO_GPIO11_OUTPUT, 0},
+#endif
};
const unsigned PX4FMU::_ngpio = sizeof(PX4FMU::_gpio_tab) / sizeof(PX4FMU::_gpio_tab[0]);
@@ -216,15 +240,18 @@ PX4FMU::PX4FMU() :
_pwm_alt_rate_channels(0),
_current_update_rate(0),
_task(-1),
- _t_actuators(-1),
- _t_actuator_armed(-1),
- _t_outputs(0),
+ _control_subs({-1}),
+ _poll_fds_num(0),
+ _armed_sub(-1),
+ _outputs_pub(-1),
_num_outputs(0),
_primary_pwm_device(false),
_task_should_exit(false),
- _armed(false),
+ _servo_armed(false),
_pwm_on(false),
_mixers(nullptr),
+ _groups_required(0),
+ _groups_subscribed(0),
_failsafe_pwm({0}),
_disarmed_pwm({0}),
_num_failsafe_set(0),
@@ -235,6 +262,14 @@ PX4FMU::PX4FMU() :
_max_pwm[i] = PWM_DEFAULT_MAX;
}
+ _control_topics[0] = ORB_ID(actuator_controls_0);
+ _control_topics[1] = ORB_ID(actuator_controls_1);
+ _control_topics[2] = ORB_ID(actuator_controls_2);
+ _control_topics[3] = ORB_ID(actuator_controls_3);
+
+ memset(_controls, 0, sizeof(_controls));
+ memset(_poll_fds, 0, sizeof(_poll_fds));
+
_debug_enabled = true;
}
@@ -365,6 +400,20 @@ PX4FMU::set_mode(Mode mode)
break;
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case MODE_8PWM: // AeroCore PWMs as 8 PWM outs
+ debug("MODE_8PWM");
+ /* default output rates */
+ _pwm_default_rate = 50;
+ _pwm_alt_rate = 50;
+ _pwm_alt_rate_channels = 0;
+
+ /* XXX magic numbers */
+ up_pwm_servo_init(0xff);
+ set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
+ break;
+#endif
+
case MODE_NONE:
debug("MODE_NONE");
@@ -447,33 +496,43 @@ PX4FMU::set_pwm_alt_channels(uint32_t channels)
return set_pwm_rate(channels, _pwm_default_rate, _pwm_alt_rate);
}
+void
+PX4FMU::subscribe()
+{
+ /* subscribe/unsubscribe to required actuator control groups */
+ uint32_t sub_groups = _groups_required & ~_groups_subscribed;
+ uint32_t unsub_groups = _groups_subscribed & ~_groups_required;
+ _poll_fds_num = 0;
+ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
+ if (sub_groups & (1 << i)) {
+ warnx("subscribe to actuator_controls_%d", i);
+ _control_subs[i] = orb_subscribe(_control_topics[i]);
+ }
+ if (unsub_groups & (1 << i)) {
+ warnx("unsubscribe from actuator_controls_%d", i);
+ ::close(_control_subs[i]);
+ _control_subs[i] = -1;
+ }
+
+ if (_control_subs[i] > 0) {
+ _poll_fds[_poll_fds_num].fd = _control_subs[i];
+ _poll_fds[_poll_fds_num].events = POLLIN;
+ _poll_fds_num++;
+ }
+ }
+}
+
void
PX4FMU::task_main()
{
- /*
- * Subscribe to the appropriate PWM output topic based on whether we are the
- * primary PWM output or not.
- */
- _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
- ORB_ID(actuator_controls_1));
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_actuator_armed, 200); /* 5Hz update rate */
+ _armed_sub = orb_subscribe(ORB_ID(actuator_armed));
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
memset(&outputs, 0, sizeof(outputs));
- /* advertise the mixed control outputs */
- _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1),
- &outputs);
-
- pollfd fds[2];
- fds[0].fd = _t_actuators;
- fds[0].events = POLLIN;
- fds[1].fd = _t_actuator_armed;
- fds[1].events = POLLIN;
#ifdef HRT_PPM_CHANNEL
// rc input, published to ORB
@@ -491,6 +550,12 @@ PX4FMU::task_main()
/* loop until killed */
while (!_task_should_exit) {
+ if (_groups_subscribed != _groups_required) {
+ subscribe();
+ _groups_subscribed = _groups_required;
+ /* force setting update rate */
+ _current_update_rate = 0;
+ }
/*
* Adjust actuator topic update rate to keep up with
@@ -515,20 +580,23 @@ PX4FMU::task_main()
}
debug("adjusted actuator update interval to %ums", update_rate_in_ms);
- orb_set_interval(_t_actuators, update_rate_in_ms);
+ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
+ if (_control_subs[i] > 0) {
+ orb_set_interval(_control_subs[i], update_rate_in_ms);
+ }
+ }
// set to current max rate, even if we are actually checking slower/faster
_current_update_rate = max_rate;
}
/* sleep waiting for data, stopping to check for PPM
- * input at 100Hz */
- int ret = ::poll(&fds[0], 2, CONTROL_INPUT_DROP_LIMIT_MS);
+ * input at 50Hz */
+ int ret = ::poll(_poll_fds, _poll_fds_num, CONTROL_INPUT_DROP_LIMIT_MS);
/* this would be bad... */
if (ret < 0) {
log("poll error %d", errno);
- usleep(1000000);
continue;
} else if (ret == 0) {
@@ -537,89 +605,101 @@ PX4FMU::task_main()
} else {
- /* do we have a control update? */
- if (fds[0].revents & POLLIN) {
-
- /* get controls - must always do this to avoid spinning */
- orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_1), _t_actuators, &_controls);
-
- /* can we mix? */
- if (_mixers != nullptr) {
-
- unsigned num_outputs;
-
- switch (_mode) {
- case MODE_2PWM:
- num_outputs = 2;
- break;
-
- case MODE_4PWM:
- num_outputs = 4;
- break;
-
- case MODE_6PWM:
- num_outputs = 6;
- break;
-
- default:
- num_outputs = 0;
- break;
+ /* get controls for required topics */
+ unsigned poll_id = 0;
+ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
+ if (_control_subs[i] > 0) {
+ if (_poll_fds[poll_id].revents & POLLIN) {
+ orb_copy(_control_topics[i], _control_subs[i], &_controls[i]);
}
-
- /* do mixing */
- outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
- outputs.timestamp = hrt_absolute_time();
-
- /* iterate actuators */
- for (unsigned i = 0; i < num_outputs; i++) {
- /* last resort: catch NaN, INF and out-of-band errors */
- if (i >= outputs.noutputs ||
- !isfinite(outputs.output[i]) ||
- outputs.output[i] < -1.0f ||
- outputs.output[i] > 1.0f) {
- /*
- * Value is NaN, INF or out of band - set to the minimum value.
- * This will be clearly visible on the servo status and will limit the risk of accidentally
- * spinning motors. It would be deadly in flight.
- */
- outputs.output[i] = -1.0f;
- }
- }
-
- uint16_t pwm_limited[num_outputs];
-
- pwm_limit_calc(_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
-
- /* output to the servos */
- for (unsigned i = 0; i < num_outputs; i++) {
- up_pwm_servo_set(i, pwm_limited[i]);
- }
-
- /* and publish for anyone that cares to see */
- orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &outputs);
+ poll_id++;
}
}
- /* how about an arming update? */
- if (fds[1].revents & POLLIN) {
- actuator_armed_s aa;
+ /* can we mix? */
+ if (_mixers != nullptr) {
- /* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &aa);
+ unsigned num_outputs;
- /* update the armed status and check that we're not locked down */
- bool set_armed = aa.armed && !aa.lockdown;
+ switch (_mode) {
+ case MODE_2PWM:
+ num_outputs = 2;
+ break;
- if (_armed != set_armed)
- _armed = set_armed;
+ case MODE_4PWM:
+ num_outputs = 4;
+ break;
- /* update PWM status if armed or if disarmed PWM values are set */
- bool pwm_on = (aa.armed || _num_disarmed_set > 0);
+ case MODE_6PWM:
+ num_outputs = 6;
+ break;
- if (_pwm_on != pwm_on) {
- _pwm_on = pwm_on;
- up_pwm_servo_arm(pwm_on);
+ case MODE_8PWM:
+ num_outputs = 8;
+ break;
+ default:
+ num_outputs = 0;
+ break;
}
+
+ /* do mixing */
+ outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
+ outputs.timestamp = hrt_absolute_time();
+
+ /* iterate actuators */
+ for (unsigned i = 0; i < num_outputs; i++) {
+ /* last resort: catch NaN, INF and out-of-band errors */
+ if (i >= outputs.noutputs ||
+ !isfinite(outputs.output[i]) ||
+ outputs.output[i] < -1.0f ||
+ outputs.output[i] > 1.0f) {
+ /*
+ * Value is NaN, INF or out of band - set to the minimum value.
+ * This will be clearly visible on the servo status and will limit the risk of accidentally
+ * spinning motors. It would be deadly in flight.
+ */
+ outputs.output[i] = -1.0f;
+ }
+ }
+
+ uint16_t pwm_limited[num_outputs];
+
+ pwm_limit_calc(_servo_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
+
+ /* output to the servos */
+ for (unsigned i = 0; i < num_outputs; i++) {
+ up_pwm_servo_set(i, pwm_limited[i]);
+ }
+
+ /* publish mixed control outputs */
+ if (_outputs_pub < 0) {
+ _outputs_pub = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), &outputs);
+ } else {
+
+ orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _outputs_pub, &outputs);
+ }
+ }
+ }
+
+ /* check arming state */
+ bool updated = false;
+ orb_check(_armed_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed);
+
+ /* update the armed status and check that we're not locked down */
+ bool set_armed = _armed.armed && !_armed.lockdown;
+
+ if (_servo_armed != set_armed)
+ _servo_armed = set_armed;
+
+ /* update PWM status if armed or if disarmed PWM values are set */
+ bool pwm_on = (_armed.armed || _num_disarmed_set > 0);
+
+ if (_pwm_on != pwm_on) {
+ _pwm_on = pwm_on;
+ up_pwm_servo_arm(pwm_on);
}
}
@@ -661,8 +741,13 @@ PX4FMU::task_main()
}
- ::close(_t_actuators);
- ::close(_t_actuator_armed);
+ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
+ if (_control_subs > 0) {
+ ::close(_control_subs[i]);
+ _control_subs[i] = -1;
+ }
+ }
+ ::close(_armed_sub);
/* make sure servos are off */
up_pwm_servo_deinit();
@@ -684,7 +769,7 @@ PX4FMU::control_callback(uintptr_t handle,
{
const actuator_controls_s *controls = (actuator_controls_s *)handle;
- input = controls->control[control_index];
+ input = controls[control_group].control[control_index];
return 0;
}
@@ -707,6 +792,9 @@ PX4FMU::ioctl(file *filp, int cmd, unsigned long arg)
case MODE_2PWM:
case MODE_4PWM:
case MODE_6PWM:
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case MODE_8PWM:
+#endif
ret = pwm_ioctl(filp, cmd, arg);
break;
@@ -736,6 +824,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_SET_ARM_OK:
case PWM_SERVO_CLEAR_ARM_OK:
+ case PWM_SERVO_SET_FORCE_SAFETY_OFF:
// these are no-ops, as no safety switch
break;
@@ -935,6 +1024,15 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
}
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case PWM_SERVO_SET(7):
+ case PWM_SERVO_SET(6):
+ if (_mode < MODE_8PWM) {
+ ret = -EINVAL;
+ break;
+ }
+#endif
+
case PWM_SERVO_SET(5):
case PWM_SERVO_SET(4):
if (_mode < MODE_6PWM) {
@@ -962,6 +1060,15 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case PWM_SERVO_GET(7):
+ case PWM_SERVO_GET(6):
+ if (_mode < MODE_8PWM) {
+ ret = -EINVAL;
+ break;
+ }
+#endif
+
case PWM_SERVO_GET(5):
case PWM_SERVO_GET(4):
if (_mode < MODE_6PWM) {
@@ -989,12 +1096,22 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_GET_RATEGROUP(3):
case PWM_SERVO_GET_RATEGROUP(4):
case PWM_SERVO_GET_RATEGROUP(5):
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case PWM_SERVO_GET_RATEGROUP(6):
+ case PWM_SERVO_GET_RATEGROUP(7):
+#endif
*(uint32_t *)arg = up_pwm_servo_get_rate_group(cmd - PWM_SERVO_GET_RATEGROUP(0));
break;
case PWM_SERVO_GET_COUNT:
case MIXERIOCGETOUTPUTCOUNT:
switch (_mode) {
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case MODE_8PWM:
+ *(unsigned *)arg = 8;
+ break;
+#endif
+
case MODE_6PWM:
*(unsigned *)arg = 6;
break;
@@ -1040,6 +1157,11 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
set_mode(MODE_6PWM);
break;
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ case 8:
+ set_mode(MODE_8PWM);
+ break;
+#endif
default:
ret = -EINVAL;
@@ -1052,6 +1174,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
if (_mixers != nullptr) {
delete _mixers;
_mixers = nullptr;
+ _groups_required = 0;
}
break;
@@ -1060,18 +1183,20 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
mixer_simple_s *mixinfo = (mixer_simple_s *)arg;
SimpleMixer *mixer = new SimpleMixer(control_callback,
- (uintptr_t)&_controls, mixinfo);
+ (uintptr_t)_controls, mixinfo);
if (mixer->check()) {
delete mixer;
+ _groups_required = 0;
ret = -EINVAL;
} else {
if (_mixers == nullptr)
_mixers = new MixerGroup(control_callback,
- (uintptr_t)&_controls);
+ (uintptr_t)_controls);
_mixers->add_mixer(mixer);
+ _mixers->groups_required(_groups_required);
}
break;
@@ -1082,9 +1207,10 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
unsigned buflen = strnlen(buf, 1024);
if (_mixers == nullptr)
- _mixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
+ _mixers = new MixerGroup(control_callback, (uintptr_t)_controls);
if (_mixers == nullptr) {
+ _groups_required = 0;
ret = -ENOMEM;
} else {
@@ -1095,7 +1221,11 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
debug("mixer load failed with %d", ret);
delete _mixers;
_mixers = nullptr;
+ _groups_required = 0;
ret = -EINVAL;
+ } else {
+
+ _mixers->groups_required(_groups_required);
}
}
@@ -1122,10 +1252,17 @@ PX4FMU::write(file *filp, const char *buffer, size_t len)
unsigned count = len / 2;
uint16_t values[6];
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ if (count > 8) {
+ // we have at most 8 outputs
+ count = 8;
+ }
+#else
if (count > 6) {
// we have at most 6 outputs
count = 6;
}
+#endif
// allow for misaligned values
memcpy(values, buffer, count * 2);
@@ -1399,6 +1536,9 @@ fmu_new_mode(PortMode new_mode)
#endif
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
servo_mode = PX4FMU::MODE_6PWM;
+#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ servo_mode = PX4FMU::MODE_8PWM;
#endif
break;
@@ -1717,7 +1857,7 @@ fmu_main(int argc, char *argv[])
fprintf(stderr, "FMU: unrecognised command %s, try:\n", verb);
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n");
-#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_AEROCORE)
fprintf(stderr, " mode_gpio, mode_pwm, test, sensor_reset [milliseconds]\n");
#endif
exit(1);
diff --git a/src/drivers/px4fmu/module.mk b/src/drivers/px4fmu/module.mk
index 05bc7a5b33..eeb59e1a1f 100644
--- a/src/drivers/px4fmu/module.mk
+++ b/src/drivers/px4fmu/module.mk
@@ -4,3 +4,5 @@
MODULE_COMMAND = fmu
SRCS = fmu.cpp
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/px4io/module.mk b/src/drivers/px4io/module.mk
index 2054faa127..c14f1f7836 100644
--- a/src/drivers/px4io/module.mk
+++ b/src/drivers/px4io/module.mk
@@ -44,3 +44,5 @@ SRCS = px4io.cpp \
# XXX prune to just get UART registers
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 7c7b3dcb7d..4099e55226 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -91,6 +91,8 @@
#include "uploader.h"
+#include "modules/dataman/dataman.h"
+
extern device::Device *PX4IO_i2c_interface() weak_function;
extern device::Device *PX4IO_serial_interface() weak_function;
@@ -527,6 +529,11 @@ PX4IO::~PX4IO()
if (_interface != nullptr)
delete _interface;
+ /* deallocate perfs */
+ perf_free(_perf_update);
+ perf_free(_perf_write);
+ perf_free(_perf_chan_count);
+
g_dev = nullptr;
}
@@ -568,9 +575,15 @@ int
PX4IO::init()
{
int ret;
+ param_t sys_restart_param;
+ int sys_restart_val = DM_INIT_REASON_VOLATILE;
ASSERT(_task == -1);
+ sys_restart_param = param_find("SYS_RESTART_TYPE");
+ /* Indicate restart type is unknown */
+ param_set(sys_restart_param, &sys_restart_val);
+
/* do regular cdev init */
ret = CDev::init();
@@ -675,6 +688,25 @@ PX4IO::init()
/* send command to arm system via command API */
vehicle_command_s cmd;
+ /* send this to itself */
+ param_t sys_id_param = param_find("MAV_SYS_ID");
+ param_t comp_id_param = param_find("MAV_COMP_ID");
+
+ int32_t sys_id;
+ int32_t comp_id;
+
+ if (param_get(sys_id_param, &sys_id)) {
+ errx(1, "PRM SYSID");
+ }
+
+ if (param_get(comp_id_param, &comp_id)) {
+ errx(1, "PRM CMPID");
+ }
+
+ cmd.target_system = sys_id;
+ cmd.target_component = comp_id;
+ cmd.source_system = sys_id;
+ cmd.source_component = comp_id;
/* request arming */
cmd.param1 = 1.0f;
cmd.param2 = 0;
@@ -684,10 +716,7 @@ PX4IO::init()
cmd.param6 = 0;
cmd.param7 = 0;
cmd.command = VEHICLE_CMD_COMPONENT_ARM_DISARM;
- // cmd.target_system = status.system_id;
- // cmd.target_component = status.component_id;
- // cmd.source_system = status.system_id;
- // cmd.source_component = status.component_id;
+
/* ask to confirm command */
cmd.confirmation = 1;
@@ -720,6 +749,11 @@ PX4IO::init()
/* keep waiting for state change for 2 s */
} while (!safety.armed);
+ /* Indicate restart type is in-flight */
+ sys_restart_val = DM_INIT_REASON_IN_FLIGHT;
+ param_set(sys_restart_param, &sys_restart_val);
+
+
/* regular boot, no in-air restart, init IO */
} else {
@@ -745,6 +779,10 @@ PX4IO::init()
}
}
+ /* Indicate restart type is power on */
+ sys_restart_val = DM_INIT_REASON_POWER_ON;
+ param_set(sys_restart_param, &sys_restart_val);
+
}
/* try to claim the generic PWM output device node as well - it's OK if we fail at this */
@@ -756,7 +794,12 @@ PX4IO::init()
}
/* start the IO interface task */
- _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 2048, (main_t)&PX4IO::task_main_trampoline, nullptr);
+ _task = task_spawn_cmd("px4io",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_ACTUATOR_OUTPUTS,
+ 2000,
+ (main_t)&PX4IO::task_main_trampoline,
+ nullptr);
if (_task < 0) {
debug("task start failed: %d", errno);
@@ -944,8 +987,27 @@ PX4IO::task_main()
int pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE, &scaling, 1);
if (pret != OK) {
- log("voltage scaling upload failed");
+ log("vscale upload failed");
}
+
+ /* send RC throttle failsafe value to IO */
+ int32_t failsafe_param_val;
+ param_t failsafe_param = param_find("RC_FAILS_THR");
+
+ if (failsafe_param != PARAM_INVALID) {
+
+ param_get(failsafe_param, &failsafe_param_val);
+
+ if (failsafe_param_val > 0) {
+
+ uint16_t failsafe_thr = failsafe_param_val;
+ pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RC_THR_FAILSAFE_US, &failsafe_thr, 1);
+ if (pret != OK) {
+ log("failsafe upload failed, FS: %d us", (int)failsafe_thr);
+ }
+ }
+ }
+
}
}
@@ -1332,12 +1394,15 @@ PX4IO::io_handle_battery(uint16_t vbatt, uint16_t ibatt)
battery_status.discharged_mah = _battery_mamphour_total;
_battery_last_timestamp = battery_status.timestamp;
- /* lazily publish the battery voltage */
- if (_to_battery > 0) {
- orb_publish(ORB_ID(battery_status), _to_battery, &battery_status);
+ /* the announced battery status would conflict with the simulated battery status in HIL */
+ if (!(_pub_blocked)) {
+ /* lazily publish the battery voltage */
+ if (_to_battery > 0) {
+ orb_publish(ORB_ID(battery_status), _to_battery, &battery_status);
- } else {
- _to_battery = orb_advertise(ORB_ID(battery_status), &battery_status);
+ } else {
+ _to_battery = orb_advertise(ORB_ID(battery_status), &battery_status);
+ }
}
}
@@ -1397,7 +1462,7 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
/* we don't have the status bits, so input_source has to be set elsewhere */
input_rc.input_source = RC_INPUT_SOURCE_UNKNOWN;
- static const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
+ const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
uint16_t regs[RC_INPUT_MAX_CHANNELS + prolog];
/*
@@ -1405,8 +1470,6 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
*
* This should be the common case (9 channel R/C control being a reasonable upper bound).
*/
- input_rc.timestamp_publication = hrt_absolute_time();
-
ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT, ®s[0], prolog + 9);
if (ret != OK)
@@ -1418,23 +1481,38 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
*/
channel_count = regs[PX4IO_P_RAW_RC_COUNT];
- if (channel_count != _rc_chan_count)
+ /* limit the channel count */
+ if (channel_count > RC_INPUT_MAX_CHANNELS) {
+ channel_count = RC_INPUT_MAX_CHANNELS;
+ }
+
+ /* count channel count changes to identify signal integrity issues */
+ if (channel_count != _rc_chan_count) {
perf_count(_perf_chan_count);
+ }
_rc_chan_count = channel_count;
+ input_rc.timestamp_publication = hrt_absolute_time();
+
input_rc.rc_ppm_frame_length = regs[PX4IO_P_RAW_RC_DATA];
input_rc.rssi = regs[PX4IO_P_RAW_RC_NRSSI];
input_rc.rc_failsafe = (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
+ input_rc.rc_lost = !(regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_OK);
input_rc.rc_lost_frame_count = regs[PX4IO_P_RAW_LOST_FRAME_COUNT];
input_rc.rc_total_frame_count = regs[PX4IO_P_RAW_FRAME_COUNT];
+ input_rc.channel_count = channel_count;
/* rc_lost has to be set before the call to this function */
- if (!input_rc.rc_lost && !input_rc.rc_failsafe)
+ if (!input_rc.rc_lost && !input_rc.rc_failsafe) {
_rc_last_valid = input_rc.timestamp_publication;
+ }
input_rc.timestamp_last_signal = _rc_last_valid;
+ /* FIELDS NOT SET HERE */
+ /* input_rc.input_source is set after this call XXX we might want to mirror the flags in the RC struct */
+
if (channel_count > 9) {
ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + 9, ®s[prolog + 9], channel_count - 9);
@@ -1442,8 +1520,10 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
return ret;
}
- input_rc.channel_count = channel_count;
- memcpy(input_rc.values, ®s[prolog], channel_count * 2);
+ /* last thing set are the actual channel values as 16 bit values */
+ for (unsigned i = 0; i < channel_count; i++) {
+ input_rc.values[i] = regs[prolog + i];
+ }
return ret;
}
@@ -1476,10 +1556,11 @@ PX4IO::io_publish_raw_rc()
} else {
rc_val.input_source = RC_INPUT_SOURCE_UNKNOWN;
- /* we do not know the RC input, only publish if RC OK flag is set */
- /* if no raw RC, just don't publish */
- if (!(_status & PX4IO_P_STATUS_FLAGS_RC_OK))
+ /* only keep publishing RC input if we ever got a valid input */
+ if (_rc_last_valid == 0) {
+ /* we have never seen valid RC signals, abort */
return OK;
+ }
}
/* lazily advertise on first publication */
@@ -1921,12 +2002,14 @@ PX4IO::print_status()
io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE));
#endif
printf("debuglevel %u\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_SET_DEBUG));
- printf("controls");
+ for (unsigned group = 0; group < 4; group++) {
+ printf("controls %u:", group);
- for (unsigned i = 0; i < _max_controls; i++)
- printf(" %u", io_reg_get(PX4IO_PAGE_CONTROLS, i));
+ for (unsigned i = 0; i < _max_controls; i++)
+ printf(" %d", (int16_t) io_reg_get(PX4IO_PAGE_CONTROLS, group * PX4IO_PROTOCOL_MAX_CONTROL_COUNT + i));
- printf("\n");
+ printf("\n");
+ }
for (unsigned i = 0; i < _max_rc_input; i++) {
unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
@@ -1957,8 +2040,7 @@ PX4IO::print_status()
}
int
-PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
-/* Make it obvious that file * isn't used here */
+PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
{
int ret = OK;
@@ -2109,6 +2191,10 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
case PWM_SERVO_GET_DISABLE_LOCKDOWN:
*(unsigned *)arg = _lockdown_override;
+
+ case PWM_SERVO_SET_FORCE_SAFETY_OFF:
+ /* force safety swith off */
+ ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC);
break;
case DSM_BIND_START:
@@ -2370,8 +2456,9 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
break;
default:
- /* not a recognized value */
- ret = -ENOTTY;
+ /* see if the parent class can make any use of it */
+ ret = CDev::ioctl(filep, cmd, arg);
+ break;
}
return ret;
diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp
index dd8abbac5a..28ec62356b 100644
--- a/src/drivers/px4io/px4io_uploader.cpp
+++ b/src/drivers/px4io/px4io_uploader.cpp
@@ -201,9 +201,14 @@ PX4IO_Uploader::upload(const char *filenames[])
continue;
}
- if (bl_rev <= 2)
+ if (bl_rev <= 2) {
ret = verify_rev2(fw_size);
- else if(bl_rev == 3) {
+ } else if(bl_rev == 3) {
+ ret = verify_rev3(fw_size);
+ } else {
+ /* verify rev 4 and higher still uses the same approach and
+ * every version *needs* to be verified.
+ */
ret = verify_rev3(fw_size);
}
diff --git a/src/drivers/rgbled/rgbled.cpp b/src/drivers/rgbled/rgbled.cpp
index 4f58891ed3..13cbfdfa8b 100644
--- a/src/drivers/rgbled/rgbled.cpp
+++ b/src/drivers/rgbled/rgbled.cpp
@@ -242,6 +242,8 @@ RGBLED::ioctl(struct file *filp, int cmd, unsigned long arg)
return OK;
default:
+ /* see if the parent class can make any use of it */
+ ret = CDev::ioctl(filp, cmd, arg);
break;
}
diff --git a/src/drivers/roboclaw/RoboClaw.cpp b/src/drivers/roboclaw/RoboClaw.cpp
index d65a9be361..dd5e4d3e0c 100644
--- a/src/drivers/roboclaw/RoboClaw.cpp
+++ b/src/drivers/roboclaw/RoboClaw.cpp
@@ -53,7 +53,7 @@
#include
#include
-#include
+#include
#include
#include
diff --git a/src/drivers/roboclaw/RoboClaw.hpp b/src/drivers/roboclaw/RoboClaw.hpp
index e9f35cf956..58994d6fa6 100644
--- a/src/drivers/roboclaw/RoboClaw.hpp
+++ b/src/drivers/roboclaw/RoboClaw.hpp
@@ -45,7 +45,7 @@
#include
#include
-#include
+#include
#include
#include
@@ -169,7 +169,7 @@ private:
struct pollfd _controlPoll;
/** actuator controls subscription */
- control::UOrbSubscription _actuators;
+ uORB::Subscription _actuators;
// private data
float _motor1Position;
diff --git a/src/modules/att_pos_estimator_ekf/module.mk b/src/drivers/sf0x/module.mk
similarity index 88%
rename from src/modules/att_pos_estimator_ekf/module.mk
rename to src/drivers/sf0x/module.mk
index 8d4a40d950..dc93a90e78 100644
--- a/src/modules/att_pos_estimator_ekf/module.mk
+++ b/src/drivers/sf0x/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+# Copyright (c) 2014 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -32,11 +32,9 @@
############################################################################
#
-# Full attitude / position Extended Kalman Filter
+# Makefile to build the Lightware laser range finder driver.
#
-MODULE_COMMAND = att_pos_estimator_ekf
+MODULE_COMMAND = sf0x
-SRCS = kalman_main.cpp \
- KalmanNav.cpp \
- params.c
+SRCS = sf0x.cpp
diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp
new file mode 100644
index 0000000000..a0cf98340a
--- /dev/null
+++ b/src/drivers/sf0x/sf0x.cpp
@@ -0,0 +1,1020 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file sf0x.cpp
+ * @author Lorenz Meier
+ * @author Greg Hulands
+ *
+ * Driver for the Lightware SF0x laser rangefinder series
+ */
+
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+
+#include
+#include
+
+#include
+
+/* Configuration Constants */
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error This requires CONFIG_SCHED_WORKQUEUE.
+#endif
+
+#define SF0X_CONVERSION_INTERVAL 83334
+#define SF0X_TAKE_RANGE_REG 'd'
+#define SF02F_MIN_DISTANCE 0.0f
+#define SF02F_MAX_DISTANCE 40.0f
+#define SF0X_DEFAULT_PORT "/dev/ttyS2"
+
+class SF0X : public device::CDev
+{
+public:
+ SF0X(const char *port = SF0X_DEFAULT_PORT);
+ virtual ~SF0X();
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ /**
+ * Diagnostics - print some basic information about the driver.
+ */
+ void print_info();
+
+protected:
+ virtual int probe();
+
+private:
+ float _min_distance;
+ float _max_distance;
+ work_s _work;
+ RingBuffer *_reports;
+ bool _sensor_ok;
+ int _measure_ticks;
+ bool _collect_phase;
+ int _fd;
+ char _linebuf[10];
+ unsigned _linebuf_index;
+ hrt_abstime _last_read;
+
+ orb_advert_t _range_finder_topic;
+
+ unsigned _consecutive_fail_count;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+ perf_counter_t _buffer_overflows;
+
+ /**
+ * Initialise the automatic measurement state machine and start it.
+ *
+ * @note This function is called at open and error time. It might make sense
+ * to make it more aggressive about resetting the bus in case of errors.
+ */
+ void start();
+
+ /**
+ * Stop the automatic measurement state machine.
+ */
+ void stop();
+
+ /**
+ * Set the min and max distance thresholds if you want the end points of the sensors
+ * range to be brought in at all, otherwise it will use the defaults SF0X_MIN_DISTANCE
+ * and SF0X_MAX_DISTANCE
+ */
+ void set_minimum_distance(float min);
+ void set_maximum_distance(float max);
+ float get_minimum_distance();
+ float get_maximum_distance();
+
+ /**
+ * Perform a poll cycle; collect from the previous measurement
+ * and start a new one.
+ */
+ void cycle();
+ int measure();
+ int collect();
+ /**
+ * Static trampoline from the workq context; because we don't have a
+ * generic workq wrapper yet.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void cycle_trampoline(void *arg);
+
+
+};
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int sf0x_main(int argc, char *argv[]);
+
+SF0X::SF0X(const char *port) :
+ CDev("SF0X", RANGE_FINDER_DEVICE_PATH),
+ _min_distance(SF02F_MIN_DISTANCE),
+ _max_distance(SF02F_MAX_DISTANCE),
+ _reports(nullptr),
+ _sensor_ok(false),
+ _measure_ticks(0),
+ _collect_phase(false),
+ _fd(-1),
+ _linebuf_index(0),
+ _last_read(0),
+ _range_finder_topic(-1),
+ _consecutive_fail_count(0),
+ _sample_perf(perf_alloc(PC_ELAPSED, "sf0x_read")),
+ _comms_errors(perf_alloc(PC_COUNT, "sf0x_comms_errors")),
+ _buffer_overflows(perf_alloc(PC_COUNT, "sf0x_buffer_overflows"))
+{
+ /* open fd */
+ _fd = ::open(port, O_RDWR | O_NOCTTY | O_NONBLOCK);
+
+ if (_fd < 0) {
+ warnx("FAIL: laser fd");
+ }
+
+ /* tell it to stop auto-triggering */
+ char stop_auto = ' ';
+ (void)::write(_fd, &stop_auto, 1);
+ usleep(100);
+ (void)::write(_fd, &stop_auto, 1);
+
+ struct termios uart_config;
+
+ int termios_state;
+
+ /* fill the struct for the new configuration */
+ tcgetattr(_fd, &uart_config);
+
+ /* clear ONLCR flag (which appends a CR for every LF) */
+ uart_config.c_oflag &= ~ONLCR;
+ /* no parity, one stop bit */
+ uart_config.c_cflag &= ~(CSTOPB | PARENB);
+
+ unsigned speed = B9600;
+
+ /* set baud rate */
+ if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
+ warnx("ERR CFG: %d ISPD", termios_state);
+ }
+
+ if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
+ warnx("ERR CFG: %d OSPD\n", termios_state);
+ }
+
+ if ((termios_state = tcsetattr(_fd, TCSANOW, &uart_config)) < 0) {
+ warnx("ERR baud %d ATTR", termios_state);
+ }
+
+ // disable debug() calls
+ _debug_enabled = false;
+
+ // work_cancel in the dtor will explode if we don't do this...
+ memset(&_work, 0, sizeof(_work));
+}
+
+SF0X::~SF0X()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ /* free any existing reports */
+ if (_reports != nullptr) {
+ delete _reports;
+ }
+}
+
+int
+SF0X::init()
+{
+ int ret = ERROR;
+ unsigned i = 0;
+
+ /* do regular cdev init */
+ if (CDev::init() != OK) {
+ goto out;
+ }
+
+ /* allocate basic report buffers */
+ _reports = new RingBuffer(2, sizeof(range_finder_report));
+
+ if (_reports == nullptr) {
+ warnx("mem err");
+ goto out;
+ }
+
+ /* get a publish handle on the range finder topic */
+ struct range_finder_report zero_report;
+ memset(&zero_report, 0, sizeof(zero_report));
+ _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &zero_report);
+
+ if (_range_finder_topic < 0) {
+ warnx("advert err");
+ }
+
+ /* close the fd */
+ ::close(_fd);
+ _fd = -1;
+out:
+ return OK;
+}
+
+int
+SF0X::probe()
+{
+ return measure();
+}
+
+void
+SF0X::set_minimum_distance(float min)
+{
+ _min_distance = min;
+}
+
+void
+SF0X::set_maximum_distance(float max)
+{
+ _max_distance = max;
+}
+
+float
+SF0X::get_minimum_distance()
+{
+ return _min_distance;
+}
+
+float
+SF0X::get_maximum_distance()
+{
+ return _max_distance;
+}
+
+int
+SF0X::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case SENSORIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _measure_ticks = 0;
+ return OK;
+
+ /* external signalling (DRDY) not supported */
+ case SENSOR_POLLRATE_EXTERNAL:
+
+ /* zero would be bad */
+ case 0:
+ return -EINVAL;
+
+ /* set default/max polling rate */
+ case SENSOR_POLLRATE_MAX:
+ case SENSOR_POLLRATE_DEFAULT: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* set interval for next measurement to minimum legal value */
+ _measure_ticks = USEC2TICK(SF0X_CONVERSION_INTERVAL);
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start) {
+ start();
+ }
+
+ return OK;
+ }
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* convert hz to tick interval via microseconds */
+ unsigned ticks = USEC2TICK(1000000 / arg);
+
+ /* check against maximum rate */
+ if (ticks < USEC2TICK(SF0X_CONVERSION_INTERVAL)) {
+ return -EINVAL;
+ }
+
+ /* update interval for next measurement */
+ _measure_ticks = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start) {
+ start();
+ }
+
+ return OK;
+ }
+ }
+ }
+
+ case SENSORIOCGPOLLRATE:
+ if (_measure_ticks == 0) {
+ return SENSOR_POLLRATE_MANUAL;
+ }
+
+ return (1000 / _measure_ticks);
+
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100)) {
+ return -EINVAL;
+ }
+
+ irqstate_t flags = irqsave();
+
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+
+ irqrestore(flags);
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _reports->size();
+
+ case SENSORIOCRESET:
+ /* XXX implement this */
+ return -EINVAL;
+
+ case RANGEFINDERIOCSETMINIUMDISTANCE: {
+ set_minimum_distance(*(float *)arg);
+ return 0;
+ }
+ break;
+
+ case RANGEFINDERIOCSETMAXIUMDISTANCE: {
+ set_maximum_distance(*(float *)arg);
+ return 0;
+ }
+ break;
+
+ default:
+ /* give it to the superclass */
+ return CDev::ioctl(filp, cmd, arg);
+ }
+}
+
+ssize_t
+SF0X::read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct range_finder_report);
+ struct range_finder_report *rbuf = reinterpret_cast(buffer);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1) {
+ return -ENOSPC;
+ }
+
+ /* if automatic measurement is enabled */
+ if (_measure_ticks > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ * Note that we may be pre-empted by the workq thread while we are doing this;
+ * we are careful to avoid racing with them.
+ */
+ while (count--) {
+ if (_reports->get(rbuf)) {
+ ret += sizeof(*rbuf);
+ rbuf++;
+ }
+ }
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement - run one conversion */
+ do {
+ _reports->flush();
+
+ /* trigger a measurement */
+ if (OK != measure()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* wait for it to complete */
+ usleep(SF0X_CONVERSION_INTERVAL);
+
+ /* run the collection phase */
+ if (OK != collect()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* state machine will have generated a report, copy it out */
+ if (_reports->get(rbuf)) {
+ ret = sizeof(*rbuf);
+ }
+
+ } while (0);
+
+ return ret;
+}
+
+int
+SF0X::measure()
+{
+ int ret;
+
+ /*
+ * Send the command to begin a measurement.
+ */
+ char cmd = SF0X_TAKE_RANGE_REG;
+ ret = ::write(_fd, &cmd, 1);
+
+ if (ret != sizeof(cmd)) {
+ perf_count(_comms_errors);
+ log("write fail %d", ret);
+ return ret;
+ }
+
+ ret = OK;
+
+ return ret;
+}
+
+int
+SF0X::collect()
+{
+ int ret;
+
+ perf_begin(_sample_perf);
+
+ /* clear buffer if last read was too long ago */
+ uint64_t read_elapsed = hrt_elapsed_time(&_last_read);
+
+ if (read_elapsed > (SF0X_CONVERSION_INTERVAL * 2)) {
+ _linebuf_index = 0;
+ } else if (_linebuf_index > 0) {
+ /* increment to next read position */
+ _linebuf_index++;
+ }
+
+ /* the buffer for read chars is buflen minus null termination */
+ unsigned readlen = sizeof(_linebuf) - 1;
+
+ /* read from the sensor (uart buffer) */
+ ret = ::read(_fd, &_linebuf[_linebuf_index], readlen - _linebuf_index);
+
+ if (ret < 0) {
+ _linebuf[sizeof(_linebuf) - 1] = '\0';
+ debug("read err: %d lbi: %d buf: %s", ret, (int)_linebuf_index, _linebuf);
+ perf_count(_comms_errors);
+ perf_end(_sample_perf);
+
+ /* only throw an error if we time out */
+ if (read_elapsed > (SF0X_CONVERSION_INTERVAL * 2)) {
+ return ret;
+
+ } else {
+ return -EAGAIN;
+ }
+ } else if (ret == 0) {
+ return -EAGAIN;
+ }
+
+ /* we did increment the index to the next position already, so just add the additional fields */
+ _linebuf_index += (ret - 1);
+
+ _last_read = hrt_absolute_time();
+
+ if (_linebuf_index < 1) {
+ /* we need at least the two end bytes to make sense of this string */
+ return -EAGAIN;
+
+ } else if (_linebuf[_linebuf_index - 1] != '\r' || _linebuf[_linebuf_index] != '\n') {
+
+ if (_linebuf_index >= readlen - 1) {
+ /* we have a full buffer, but no line ending - abort */
+ _linebuf_index = 0;
+ perf_count(_comms_errors);
+ return -ENOMEM;
+ } else {
+ /* incomplete read, reschedule ourselves */
+ return -EAGAIN;
+ }
+ }
+
+ char *end;
+ float si_units;
+ bool valid;
+
+ /* enforce line ending */
+ unsigned lend = (_linebuf_index < (sizeof(_linebuf) - 1)) ? _linebuf_index : (sizeof(_linebuf) - 1);
+
+ _linebuf[lend] = '\0';
+
+ if (_linebuf[0] == '-' && _linebuf[1] == '-' && _linebuf[2] == '.') {
+ si_units = -1.0f;
+ valid = false;
+
+ } else {
+
+ /* we need to find a dot in the string, as we're missing the meters part else */
+ valid = false;
+
+ /* wipe out partially read content from last cycle(s), check for dot */
+ for (int i = 0; i < (lend - 2); i++) {
+ if (_linebuf[i] == '\n') {
+ char buf[sizeof(_linebuf)];
+ memcpy(buf, &_linebuf[i+1], (lend + 1) - (i + 1));
+ memcpy(_linebuf, buf, (lend + 1) - (i + 1));
+ }
+
+ if (_linebuf[i] == '.') {
+ valid = true;
+ }
+ }
+
+ if (valid) {
+ si_units = strtod(_linebuf, &end);
+
+ /* we require at least 3 characters for a valid number */
+ if (end > _linebuf + 3) {
+ valid = true;
+ } else {
+ si_units = -1.0f;
+ valid = false;
+ }
+ }
+ }
+
+ debug("val (float): %8.4f, raw: %s, valid: %s\n", si_units, _linebuf, ((valid) ? "OK" : "NO"));
+
+ /* done with this chunk, resetting - even if invalid */
+ _linebuf_index = 0;
+
+ /* if its invalid, there is no reason to forward the value */
+ if (!valid) {
+ perf_count(_comms_errors);
+ return -EINVAL;
+ }
+
+ struct range_finder_report report;
+
+ /* this should be fairly close to the end of the measurement, so the best approximation of the time */
+ report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
+ report.distance = si_units;
+ report.valid = valid && (si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0);
+
+ /* publish it */
+ orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
+
+ if (_reports->force(&report)) {
+ perf_count(_buffer_overflows);
+ }
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ ret = OK;
+
+ perf_end(_sample_perf);
+ return ret;
+}
+
+void
+SF0X::start()
+{
+ /* reset the report ring and state machine */
+ _collect_phase = false;
+ _reports->flush();
+
+ /* schedule a cycle to start things */
+ work_queue(HPWORK, &_work, (worker_t)&SF0X::cycle_trampoline, this, 1);
+
+ // /* notify about state change */
+ // struct subsystem_info_s info = {
+ // true,
+ // true,
+ // true,
+ // SUBSYSTEM_TYPE_RANGEFINDER
+ // };
+ // static orb_advert_t pub = -1;
+
+ // if (pub > 0) {
+ // orb_publish(ORB_ID(subsystem_info), pub, &info);
+
+ // } else {
+ // pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ // }
+}
+
+void
+SF0X::stop()
+{
+ work_cancel(HPWORK, &_work);
+}
+
+void
+SF0X::cycle_trampoline(void *arg)
+{
+ SF0X *dev = static_cast(arg);
+
+ dev->cycle();
+}
+
+void
+SF0X::cycle()
+{
+ /* fds initialized? */
+ if (_fd < 0) {
+ /* open fd */
+ _fd = ::open(SF0X_DEFAULT_PORT, O_RDWR | O_NOCTTY | O_NONBLOCK);
+ }
+
+ /* collection phase? */
+ if (_collect_phase) {
+
+ /* perform collection */
+ int collect_ret = collect();
+
+ if (collect_ret == -EAGAIN) {
+ /* reschedule to grab the missing bits, time to transmit 10 bytes @9600 bps */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&SF0X::cycle_trampoline,
+ this,
+ USEC2TICK(1100));
+ return;
+ }
+
+ if (OK != collect_ret) {
+
+ /* we know the sensor needs about four seconds to initialize */
+ if (hrt_absolute_time() > 5 * 1000 * 1000LL && _consecutive_fail_count < 5) {
+ log("collection error #%u", _consecutive_fail_count);
+ }
+ _consecutive_fail_count++;
+
+ /* restart the measurement state machine */
+ start();
+ return;
+ } else {
+ /* apparently success */
+ _consecutive_fail_count = 0;
+ }
+
+ /* next phase is measurement */
+ _collect_phase = false;
+
+ /*
+ * Is there a collect->measure gap?
+ */
+ if (_measure_ticks > USEC2TICK(SF0X_CONVERSION_INTERVAL)) {
+
+ /* schedule a fresh cycle call when we are ready to measure again */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&SF0X::cycle_trampoline,
+ this,
+ _measure_ticks - USEC2TICK(SF0X_CONVERSION_INTERVAL));
+
+ return;
+ }
+ }
+
+ /* measurement phase */
+ if (OK != measure()) {
+ log("measure error");
+ }
+
+ /* next phase is collection */
+ _collect_phase = true;
+
+ /* schedule a fresh cycle call when the measurement is done */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&SF0X::cycle_trampoline,
+ this,
+ USEC2TICK(SF0X_CONVERSION_INTERVAL));
+}
+
+void
+SF0X::print_info()
+{
+ perf_print_counter(_sample_perf);
+ perf_print_counter(_comms_errors);
+ perf_print_counter(_buffer_overflows);
+ printf("poll interval: %d ticks\n", _measure_ticks);
+ _reports->print_info("report queue");
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace sf0x
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+const int ERROR = -1;
+
+SF0X *g_dev;
+
+void start();
+void stop();
+void test();
+void reset();
+void info();
+
+/**
+ * Start the driver.
+ */
+void
+start(const char *port)
+{
+ int fd;
+
+ if (g_dev != nullptr) {
+ errx(1, "already started");
+ }
+
+ /* create the driver */
+ g_dev = new SF0X(port);
+
+ if (g_dev == nullptr) {
+ goto fail;
+ }
+
+ if (OK != g_dev->init()) {
+ goto fail;
+ }
+
+ /* set the poll rate to default, starts automatic data collection */
+ fd = open(RANGE_FINDER_DEVICE_PATH, 0);
+
+ if (fd < 0) {
+ warnx("device open fail");
+ goto fail;
+ }
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
+ goto fail;
+ }
+
+ exit(0);
+
+fail:
+
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+ }
+
+ errx(1, "driver start failed");
+}
+
+/**
+ * Stop the driver
+ */
+void stop()
+{
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+
+ } else {
+ errx(1, "driver not running");
+ }
+
+ exit(0);
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ */
+void
+test()
+{
+ struct range_finder_report report;
+ ssize_t sz;
+
+ int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ err(1, "%s open failed (try 'sf0x start' if the driver is not running", RANGE_FINDER_DEVICE_PATH);
+ }
+
+ /* do a simple demand read */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report)) {
+ err(1, "immediate read failed");
+ }
+
+ warnx("single read");
+ warnx("val: %0.2f m", (double)report.distance);
+ warnx("time: %lld", report.timestamp);
+
+ /* start the sensor polling at 2 Hz rate */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
+ errx(1, "failed to set 2Hz poll rate");
+ }
+
+ /* read the sensor 5x and report each value */
+ for (unsigned i = 0; i < 5; i++) {
+ struct pollfd fds;
+
+ /* wait for data to be ready */
+ fds.fd = fd;
+ fds.events = POLLIN;
+ int ret = poll(&fds, 1, 2000);
+
+ if (ret != 1) {
+ warnx("timed out");
+ break;
+ }
+
+ /* now go get it */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report)) {
+ warnx("read failed: got %d vs exp. %d", sz, sizeof(report));
+ break;
+ }
+
+ warnx("read #%u", i);
+ warnx("val: %0.3f m", (double)report.distance);
+ warnx("time: %lld", report.timestamp);
+ }
+
+ /* reset the sensor polling to the default rate */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
+ errx(1, "ERR: DEF RATE");
+ }
+
+ errx(0, "PASS");
+}
+
+/**
+ * Reset the driver.
+ */
+void
+reset()
+{
+ int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ err(1, "failed ");
+ }
+
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
+ err(1, "driver reset failed");
+ }
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
+ err(1, "driver poll restart failed");
+ }
+
+ exit(0);
+}
+
+/**
+ * Print a little info about the driver.
+ */
+void
+info()
+{
+ if (g_dev == nullptr) {
+ errx(1, "driver not running");
+ }
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ exit(0);
+}
+
+} // namespace
+
+int
+sf0x_main(int argc, char *argv[])
+{
+ /*
+ * Start/load the driver.
+ */
+ if (!strcmp(argv[1], "start")) {
+ if (argc > 2) {
+ sf0x::start(argv[2]);
+
+ } else {
+ sf0x::start(SF0X_DEFAULT_PORT);
+ }
+ }
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop")) {
+ sf0x::stop();
+ }
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test")) {
+ sf0x::test();
+ }
+
+ /*
+ * Reset the driver.
+ */
+ if (!strcmp(argv[1], "reset")) {
+ sf0x::reset();
+ }
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
+ sf0x::info();
+ }
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
+}
diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp
index 00e46d6b82..de13b89697 100644
--- a/src/drivers/stm32/adc/adc.cpp
+++ b/src/drivers/stm32/adc/adc.cpp
@@ -41,6 +41,7 @@
*/
#include
+#include
#include
#include
@@ -64,6 +65,8 @@
#include
#include
+#include
+
/*
* Register accessors.
* For now, no reason not to just use ADC1.
@@ -119,6 +122,8 @@ private:
unsigned _channel_count;
adc_msg_s *_samples; /**< sample buffer */
+ orb_advert_t _to_system_power;
+
/** work trampoline */
static void _tick_trampoline(void *arg);
@@ -134,13 +139,16 @@ private:
*/
uint16_t _sample(unsigned channel);
+ // update system_power ORB topic, only on FMUv2
+ void update_system_power(void);
};
ADC::ADC(uint32_t channels) :
CDev("adc", ADC_DEVICE_PATH),
_sample_perf(perf_alloc(PC_ELAPSED, "ADC samples")),
_channel_count(0),
- _samples(nullptr)
+ _samples(nullptr),
+ _to_system_power(0)
{
_debug_enabled = true;
@@ -290,6 +298,43 @@ ADC::_tick()
/* scan the channel set and sample each */
for (unsigned i = 0; i < _channel_count; i++)
_samples[i].am_data = _sample(_samples[i].am_channel);
+ update_system_power();
+}
+
+void
+ADC::update_system_power(void)
+{
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ system_power_s system_power;
+ system_power.timestamp = hrt_absolute_time();
+
+ system_power.voltage5V_v = 0;
+ for (unsigned i = 0; i < _channel_count; i++) {
+ if (_samples[i].am_channel == 4) {
+ // it is 2:1 scaled
+ system_power.voltage5V_v = _samples[i].am_data * (6.6f / 4096);
+ }
+ }
+
+ // these are not ADC related, but it is convenient to
+ // publish these to the same topic
+ system_power.usb_connected = stm32_gpioread(GPIO_OTGFS_VBUS);
+
+ // note that the valid pins are active low
+ system_power.brick_valid = !stm32_gpioread(GPIO_VDD_BRICK_VALID);
+ system_power.servo_valid = !stm32_gpioread(GPIO_VDD_SERVO_VALID);
+
+ // OC pins are active low
+ system_power.periph_5V_OC = !stm32_gpioread(GPIO_VDD_5V_PERIPH_OC);
+ system_power.hipower_5V_OC = !stm32_gpioread(GPIO_VDD_5V_HIPOWER_OC);
+
+ /* lazily publish */
+ if (_to_system_power > 0) {
+ orb_publish(ORB_ID(system_power), _to_system_power, &system_power);
+ } else {
+ _to_system_power = orb_advertise(ORB_ID(system_power), &system_power);
+ }
+#endif // CONFIG_ARCH_BOARD_PX4FMU_V2
}
uint16_t
@@ -341,7 +386,7 @@ test(void)
err(1, "can't open ADC device");
for (unsigned i = 0; i < 50; i++) {
- adc_msg_s data[10];
+ adc_msg_s data[12];
ssize_t count = read(fd, data, sizeof(data));
if (count < 0)
@@ -374,6 +419,10 @@ adc_main(int argc, char *argv[])
g_adc = new ADC((1 << 2) | (1 << 3) | (1 << 4) |
(1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15));
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ /* XXX this hardcodes the default channel set for AeroCore - should be configurable */
+ g_adc = new ADC((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
+#endif
if (g_adc == nullptr)
errx(1, "couldn't allocate the ADC driver");
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index b7c9b89a45..281f918d70 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -94,7 +94,7 @@
#elif HRT_TIMER == 3
# define HRT_TIMER_BASE STM32_TIM3_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
-# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM3EN
+# define HRT_TIMER_POWER_BIT RCC_APB1ENR_TIM3EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM3
# define HRT_TIMER_CLOCK STM32_APB1_TIM3_CLKIN
# if CONFIG_STM32_TIM3
@@ -141,7 +141,7 @@
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM10EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1UP
-# define HRT_TIMER_CLOCK STM32_APB1_TIM10_CLKIN
+# define HRT_TIMER_CLOCK STM32_APB2_TIM10_CLKIN
# if CONFIG_STM32_TIM10
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=10
# endif
@@ -150,7 +150,7 @@
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM11EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1TRGCOM
-# define HRT_TIMER_CLOCK STM32_APB1_TIM11_CLKIN
+# define HRT_TIMER_CLOCK STM32_APB2_TIM11_CLKIN
# if CONFIG_STM32_TIM11
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
# endif
@@ -354,6 +354,9 @@ __EXPORT uint16_t ppm_frame_length = 0;
__EXPORT unsigned ppm_decoded_channels = 0;
__EXPORT uint64_t ppm_last_valid_decode = 0;
+#define PPM_DEBUG 0
+
+#if PPM_DEBUG
/* PPM edge history */
__EXPORT uint16_t ppm_edge_history[32];
unsigned ppm_edge_next;
@@ -361,6 +364,7 @@ unsigned ppm_edge_next;
/* PPM pulse history */
__EXPORT uint16_t ppm_pulse_history[32];
unsigned ppm_pulse_next;
+#endif
static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
@@ -455,10 +459,12 @@ hrt_ppm_decode(uint32_t status)
/* how long since the last edge? - this handles counter wrapping implicitely. */
width = count - ppm.last_edge;
+#if PPM_DEBUG
ppm_edge_history[ppm_edge_next++] = width;
if (ppm_edge_next >= 32)
ppm_edge_next = 0;
+#endif
/*
* if this looks like a start pulse, then push the last set of values
@@ -546,10 +552,12 @@ hrt_ppm_decode(uint32_t status)
interval = count - ppm.last_mark;
ppm.last_mark = count;
+#if PPM_DEBUG
ppm_pulse_history[ppm_pulse_next++] = interval;
if (ppm_pulse_next >= 32)
ppm_pulse_next = 0;
+#endif
/* if the mark-mark timing is out of bounds, abandon the frame */
if ((interval < PPM_MIN_CHANNEL_VALUE) || (interval > PPM_MAX_CHANNEL_VALUE))
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index f36f2091e3..810f4aacc4 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -334,6 +334,8 @@ ToneAlarm::ToneAlarm() :
_default_tunes[TONE_BATTERY_WARNING_SLOW_TUNE] = "MBNT100a8"; //battery warning slow
_default_tunes[TONE_BATTERY_WARNING_FAST_TUNE] = "MBNT255a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8"; //battery warning fast
_default_tunes[TONE_GPS_WARNING_TUNE] = "MFT255L4AAAL1F#"; //gps warning slow
+ _default_tunes[TONE_ARMING_FAILURE_TUNE] = "MFT255L4<<
#include
#include
+#include
#include
#include "flow_position_estimator_params.h"
@@ -109,9 +110,9 @@ int flow_position_estimator_main(int argc, char *argv[])
thread_should_exit = false;
daemon_task = task_spawn_cmd("flow_position_estimator",
- SCHED_RR,
+ SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 4096,
+ 4000,
flow_position_estimator_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/examples/px4_daemon_app/module.mk b/src/examples/px4_daemon_app/module.mk
index 5f8aa73d57..fc42231425 100644
--- a/src/examples/px4_daemon_app/module.mk
+++ b/src/examples/px4_daemon_app/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = px4_daemon_app
SRCS = px4_daemon_app.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c
index 53f1b4a9a7..3eaf14148a 100644
--- a/src/examples/px4_daemon_app/px4_daemon_app.c
+++ b/src/examples/px4_daemon_app/px4_daemon_app.c
@@ -98,7 +98,7 @@ int px4_daemon_app_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("daemon",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 4096,
+ 2000,
px4_daemon_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/examples/px4_mavlink_debug/module.mk b/src/examples/px4_mavlink_debug/module.mk
index fefd614961..c7ef97fc45 100644
--- a/src/examples/px4_mavlink_debug/module.mk
+++ b/src/examples/px4_mavlink_debug/module.mk
@@ -37,4 +37,6 @@
MODULE_COMMAND = px4_mavlink_debug
-SRCS = px4_mavlink_debug.c
\ No newline at end of file
+SRCS = px4_mavlink_debug.c
+
+MODULE_STACKSIZE = 2000
diff --git a/src/modules/controllib/block/List.hpp b/src/include/containers/List.hpp
similarity index 96%
rename from src/modules/controllib/block/List.hpp
rename to src/include/containers/List.hpp
index 96b0b94d10..13cbda9382 100644
--- a/src/modules/controllib/block/List.hpp
+++ b/src/include/containers/List.hpp
@@ -32,9 +32,9 @@
****************************************************************************/
/**
- * @file Node.h
+ * @file List.hpp
*
- * A node of a linked list.
+ * A linked list.
*/
#pragma once
@@ -43,7 +43,7 @@ template
class __EXPORT ListNode
{
public:
- ListNode() : _sibling(NULL) {
+ ListNode() : _sibling(nullptr) {
}
void setSibling(T sibling) { _sibling = sibling; }
T getSibling() { return _sibling; }
diff --git a/src/include/mavlink/mavlink_log.h b/src/include/mavlink/mavlink_log.h
index 5054937e07..0ea655cac3 100644
--- a/src/include/mavlink/mavlink_log.h
+++ b/src/include/mavlink/mavlink_log.h
@@ -100,6 +100,7 @@ __EXPORT void mavlink_vasprintf(int _fd, int severity, const char *fmt, ...);
*/
#define mavlink_log_info(_fd, _text, ...) mavlink_vasprintf(_fd, MAVLINK_IOC_SEND_TEXT_INFO, _text, ##__VA_ARGS__);
+
struct mavlink_logmessage {
char text[MAVLINK_LOG_MAXLEN + 1];
unsigned char severity;
@@ -112,6 +113,7 @@ struct mavlink_logbuffer {
struct mavlink_logmessage *elems;
};
+__BEGIN_DECLS
void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size);
void mavlink_logbuffer_destroy(struct mavlink_logbuffer *lb);
@@ -125,6 +127,7 @@ void mavlink_logbuffer_write(struct mavlink_logbuffer *lb, const struct mavlink_
int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessage *elem);
void mavlink_logbuffer_vasprintf(struct mavlink_logbuffer *lb, int severity, const char *fmt, ...);
+__END_DECLS
#endif
diff --git a/src/lib/geo/geo.c b/src/lib/geo/geo.c
index 9b3e202e6e..9a24ff50e2 100644
--- a/src/lib/geo/geo.c
+++ b/src/lib/geo/geo.c
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler
- * Julian Oes
- * Lorenz Meier
+ * Copyright (C) 2012, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -42,6 +39,7 @@
* @author Thomas Gubler
* @author Julian Oes
* @author Lorenz Meier
+ * @author Anton Babushkin
*/
#include
@@ -52,124 +50,58 @@
#include
#include
+/*
+ * Azimuthal Equidistant Projection
+ * formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html
+ */
-/* values for map projection */
-static double phi_1;
-static double sin_phi_1;
-static double cos_phi_1;
-static double lambda_0;
-static double scale;
-
-__EXPORT void map_projection_init(double lat_0, double lon_0) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
+__EXPORT void map_projection_init(struct map_projection_reference_s *ref, double lat_0, double lon_0) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
{
- /* notation and formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
- phi_1 = lat_0 / 180.0 * M_PI;
- lambda_0 = lon_0 / 180.0 * M_PI;
-
- sin_phi_1 = sin(phi_1);
- cos_phi_1 = cos(phi_1);
-
- /* calculate local scale by using the relation of true distance and the distance on plane */ //TODO: this is a quick solution, there are probably easier ways to determine the scale
-
- /* 1) calculate true distance d on sphere to a point: http://www.movable-type.co.uk/scripts/latlong.html */
-
- double lat1 = phi_1;
- double lon1 = lambda_0;
-
- double lat2 = phi_1 + 0.5 / 180 * M_PI;
- double lon2 = lambda_0 + 0.5 / 180 * M_PI;
- double sin_lat_2 = sin(lat2);
- double cos_lat_2 = cos(lat2);
- double d = acos(sin(lat1) * sin_lat_2 + cos(lat1) * cos_lat_2 * cos(lon2 - lon1)) * CONSTANTS_RADIUS_OF_EARTH;
-
- /* 2) calculate distance rho on plane */
- double k_bar = 0;
- double c = acos(sin_phi_1 * sin_lat_2 + cos_phi_1 * cos_lat_2 * cos(lon2 - lambda_0));
-
- if (0 != c)
- k_bar = c / sin(c);
-
- double x2 = k_bar * (cos_lat_2 * sin(lon2 - lambda_0)); //Projection of point 2 on plane
- double y2 = k_bar * ((cos_phi_1 * sin_lat_2 - sin_phi_1 * cos_lat_2 * cos(lon2 - lambda_0)));
- double rho = sqrt(pow(x2, 2) + pow(y2, 2));
-
- scale = d / rho;
+ ref->lat = lat_0 / 180.0 * M_PI;
+ ref->lon = lon_0 / 180.0 * M_PI;
+ ref->sin_lat = sin(ref->lat);
+ ref->cos_lat = cos(ref->lat);
}
-__EXPORT void map_projection_project(double lat, double lon, float *x, float *y)
+__EXPORT void map_projection_project(struct map_projection_reference_s *ref, double lat, double lon, float *x, float *y)
{
- /* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
- double phi = lat / 180.0 * M_PI;
- double lambda = lon / 180.0 * M_PI;
+ double lat_rad = lat / 180.0 * M_PI;
+ double lon_rad = lon / 180.0 * M_PI;
- double sin_phi = sin(phi);
- double cos_phi = cos(phi);
+ double sin_lat = sin(lat_rad);
+ double cos_lat = cos(lat_rad);
+ double cos_d_lon = cos(lon_rad - ref->lon);
- double k_bar = 0;
- /* using small angle approximation (formula in comment is without aproximation) */
- double c = acos(sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2)); //double c = acos( sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * cos(lambda - lambda_0) );
+ double c = acos(ref->sin_lat * sin_lat + ref->cos_lat * cos_lat * cos_d_lon);
+ double k = (c == 0.0) ? 1.0 : (c / sin(c));
- if (0 != c)
- k_bar = c / sin(c);
-
- /* using small angle approximation (formula in comment is without aproximation) */
- *y = k_bar * (cos_phi * (lambda - lambda_0)) * scale;//*y = k_bar * (cos_phi * sin(lambda - lambda_0)) * scale;
- *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2))) * scale; // *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * cos(lambda - lambda_0))) * scale;
-
-// printf("%phi_1=%.10f, lambda_0 =%.10f\n", phi_1, lambda_0);
+ *x = k * (ref->cos_lat * sin_lat - ref->sin_lat * cos_lat * cos_d_lon) * CONSTANTS_RADIUS_OF_EARTH;
+ *y = k * cos_lat * sin(lon_rad - ref->lon) * CONSTANTS_RADIUS_OF_EARTH;
}
-__EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon)
+__EXPORT void map_projection_reproject(struct map_projection_reference_s *ref, float x, float y, double *lat, double *lon)
{
- /* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
-
- double x_descaled = x / scale;
- double y_descaled = y / scale;
-
- double c = sqrt(pow(x_descaled, 2) + pow(y_descaled, 2));
+ float x_rad = x / CONSTANTS_RADIUS_OF_EARTH;
+ float y_rad = y / CONSTANTS_RADIUS_OF_EARTH;
+ double c = sqrtf(x_rad * x_rad + y_rad * y_rad);
double sin_c = sin(c);
double cos_c = cos(c);
- double lat_sphere = 0;
+ double lat_rad;
+ double lon_rad;
- if (c != 0)
- lat_sphere = asin(cos_c * sin_phi_1 + (x_descaled * sin_c * cos_phi_1) / c);
- else
- lat_sphere = asin(cos_c * sin_phi_1);
-
-// printf("lat_sphere = %.10f\n",lat_sphere);
-
- double lon_sphere = 0;
-
- if (phi_1 == M_PI / 2) {
- //using small angle approximation (formula in comment is without aproximation)
- lon_sphere = (lambda_0 - y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(-y_descaled, x_descaled));
-
- } else if (phi_1 == -M_PI / 2) {
- //using small angle approximation (formula in comment is without aproximation)
- lon_sphere = (lambda_0 + y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(y_descaled, x_descaled));
+ if (c != 0.0) {
+ lat_rad = asin(cos_c * ref->sin_lat + (x_rad * sin_c * ref->cos_lat) / c);
+ lon_rad = (ref->lon + atan2(y_rad * sin_c, c * ref->cos_lat * cos_c - x_rad * ref->sin_lat * sin_c));
} else {
-
- lon_sphere = (lambda_0 + atan2(y_descaled * sin_c , c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c));
- //using small angle approximation
-// double denominator = (c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c);
-// if(denominator != 0)
-// {
-// lon_sphere = (lambda_0 + (y_descaled * sin_c) / denominator);
-// }
-// else
-// {
-// ...
-// }
+ lat_rad = ref->lat;
+ lon_rad = ref->lon;
}
-// printf("lon_sphere = %.10f\n",lon_sphere);
-
- *lat = lat_sphere * 180.0 / M_PI;
- *lon = lon_sphere * 180.0 / M_PI;
-
+ *lat = lat_rad * 180.0 / M_PI;
+ *lon = lon_rad * 180.0 / M_PI;
}
@@ -197,7 +129,6 @@ __EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, doub
double lat_next_rad = lat_next * M_DEG_TO_RAD;
double lon_next_rad = lon_next * M_DEG_TO_RAD;
- double d_lat = lat_next_rad - lat_now_rad;
double d_lon = lon_next_rad - lon_now_rad;
/* conscious mix of double and float trig function to maximize speed and efficiency */
@@ -208,7 +139,7 @@ __EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, doub
return theta;
}
-__EXPORT void get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next, float* v_n, float* v_e)
+__EXPORT void get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n, float *v_e)
{
double lat_now_rad = lat_now * M_DEG_TO_RAD;
double lon_now_rad = lon_now * M_DEG_TO_RAD;
@@ -223,7 +154,7 @@ __EXPORT void get_vector_to_next_waypoint(double lat_now, double lon_now, double
*v_e = CONSTANTS_RADIUS_OF_EARTH * sin(d_lon) * cos(lat_next_rad);
}
-__EXPORT void get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next, double lon_next, float* v_n, float* v_e)
+__EXPORT void get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n, float *v_e)
{
double lat_now_rad = lat_now * M_DEG_TO_RAD;
double lon_now_rad = lon_now * M_DEG_TO_RAD;
@@ -249,7 +180,7 @@ __EXPORT void add_vector_to_global_position(double lat_now, double lon_now, floa
// Additional functions - @author Doug Weibel
-__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end)
+__EXPORT int get_distance_to_line(struct crosstrack_error_s *crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end)
{
// This function returns the distance to the nearest point on the track line. Distance is positive if current
// position is right of the track and negative if left of the track as seen from a point on the track line
@@ -266,7 +197,7 @@ __EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error,
crosstrack_error->bearing = 0.0f;
// Return error if arguments are bad
- if (lat_now == 0.0d || lon_now == 0.0d || lat_start == 0.0d || lon_start == 0.0d || lat_end == 0.0d || lon_end == 0.0d) return return_value;
+ if (lat_now == 0.0d || lon_now == 0.0d || lat_start == 0.0d || lon_start == 0.0d || lat_end == 0.0d || lon_end == 0.0d) { return return_value; }
bearing_end = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
bearing_track = get_bearing_to_next_waypoint(lat_start, lon_start, lat_end, lon_end);
@@ -297,8 +228,8 @@ __EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error,
}
-__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
- float radius, float arc_start_bearing, float arc_sweep)
+__EXPORT int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
+ float radius, float arc_start_bearing, float arc_sweep)
{
// This function returns the distance to the nearest point on the track arc. Distance is positive if current
// position is right of the arc and negative if left of the arc as seen from the closest point on the arc and
@@ -317,29 +248,29 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, d
crosstrack_error->bearing = 0.0f;
// Return error if arguments are bad
- if (lat_now == 0.0d || lon_now == 0.0d || lat_center == 0.0d || lon_center == 0.0d || radius == 0.0d) return return_value;
+ if (lat_now == 0.0d || lon_now == 0.0d || lat_center == 0.0d || lon_center == 0.0d || radius == 0.0d) { return return_value; }
if (arc_sweep >= 0) {
bearing_sector_start = arc_start_bearing;
bearing_sector_end = arc_start_bearing + arc_sweep;
- if (bearing_sector_end > 2.0f * M_PI_F) bearing_sector_end -= M_TWOPI_F;
+ if (bearing_sector_end > 2.0f * M_PI_F) { bearing_sector_end -= M_TWOPI_F; }
} else {
bearing_sector_end = arc_start_bearing;
bearing_sector_start = arc_start_bearing - arc_sweep;
- if (bearing_sector_start < 0.0f) bearing_sector_start += M_TWOPI_F;
+ if (bearing_sector_start < 0.0f) { bearing_sector_start += M_TWOPI_F; }
}
in_sector = false;
// Case where sector does not span zero
- if (bearing_sector_end >= bearing_sector_start && bearing_now >= bearing_sector_start && bearing_now <= bearing_sector_end) in_sector = true;
+ if (bearing_sector_end >= bearing_sector_start && bearing_now >= bearing_sector_start && bearing_now <= bearing_sector_end) { in_sector = true; }
// Case where sector does span zero
- if (bearing_sector_end < bearing_sector_start && (bearing_now > bearing_sector_start || bearing_now < bearing_sector_end)) in_sector = true;
+ if (bearing_sector_end < bearing_sector_start && (bearing_now > bearing_sector_start || bearing_now < bearing_sector_end)) { in_sector = true; }
// If in the sector then calculate distance and bearing to closest point
if (in_sector) {
@@ -395,8 +326,8 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, d
}
__EXPORT float get_distance_to_point_global_wgs84(double lat_now, double lon_now, float alt_now,
- double lat_next, double lon_next, float alt_next,
- float *dist_xy, float *dist_z)
+ double lat_next, double lon_next, float alt_next,
+ float *dist_xy, float *dist_z)
{
double current_x_rad = lat_next / 180.0 * M_PI;
double current_y_rad = lon_next / 180.0 * M_PI;
@@ -420,8 +351,8 @@ __EXPORT float get_distance_to_point_global_wgs84(double lat_now, double lon_now
__EXPORT float mavlink_wpm_distance_to_point_local(float x_now, float y_now, float z_now,
- float x_next, float y_next, float z_next,
- float *dist_xy, float *dist_z)
+ float x_next, float y_next, float z_next,
+ float *dist_xy, float *dist_z)
{
float dx = x_now - x_next;
float dy = y_now - y_next;
@@ -441,17 +372,21 @@ __EXPORT float _wrap_pi(float bearing)
}
int c = 0;
- while (bearing > M_PI_F) {
+ while (bearing >= M_PI_F) {
bearing -= M_TWOPI_F;
- if (c++ > 3)
+
+ if (c++ > 3) {
return NAN;
+ }
}
c = 0;
- while (bearing <= -M_PI_F) {
+ while (bearing < -M_PI_F) {
bearing += M_TWOPI_F;
- if (c++ > 3)
+
+ if (c++ > 3) {
return NAN;
+ }
}
return bearing;
@@ -465,17 +400,21 @@ __EXPORT float _wrap_2pi(float bearing)
}
int c = 0;
- while (bearing > M_TWOPI_F) {
+ while (bearing >= M_TWOPI_F) {
bearing -= M_TWOPI_F;
- if (c++ > 3)
+
+ if (c++ > 3) {
return NAN;
+ }
}
c = 0;
- while (bearing <= 0.0f) {
+ while (bearing < 0.0f) {
bearing += M_TWOPI_F;
- if (c++ > 3)
+
+ if (c++ > 3) {
return NAN;
+ }
}
return bearing;
@@ -489,17 +428,21 @@ __EXPORT float _wrap_180(float bearing)
}
int c = 0;
- while (bearing > 180.0f) {
+ while (bearing >= 180.0f) {
bearing -= 360.0f;
- if (c++ > 3)
+
+ if (c++ > 3) {
return NAN;
+ }
}
c = 0;
- while (bearing <= -180.0f) {
+ while (bearing < -180.0f) {
bearing += 360.0f;
- if (c++ > 3)
+
+ if (c++ > 3) {
return NAN;
+ }
}
return bearing;
@@ -513,17 +456,21 @@ __EXPORT float _wrap_360(float bearing)
}
int c = 0;
- while (bearing > 360.0f) {
+ while (bearing >= 360.0f) {
bearing -= 360.0f;
- if (c++ > 3)
+
+ if (c++ > 3) {
return NAN;
+ }
}
c = 0;
- while (bearing <= 0.0f) {
+ while (bearing < 0.0f) {
bearing += 360.0f;
- if (c++ > 3)
+
+ if (c++ > 3) {
return NAN;
+ }
}
return bearing;
diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h
index 94afb4df0a..e2f3da6f80 100644
--- a/src/lib/geo/geo.h
+++ b/src/lib/geo/geo.h
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler
- * Julian Oes
- * Lorenz Meier
+ * Copyright (C) 2012, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -42,6 +39,7 @@
* @author Thomas Gubler
* @author Julian Oes
* @author Lorenz Meier
+ * @author Anton Babushkin
* Additional functions - @author Doug Weibel
*/
@@ -52,6 +50,8 @@
__BEGIN_DECLS
+#include "geo/geo_mag_declination.h"
+
#include
#define CONSTANTS_ONE_G 9.80665f /* m/s^2 */
@@ -67,6 +67,14 @@ struct crosstrack_error_s {
float bearing; // Bearing in radians to closest point on line/arc
} ;
+/* lat/lon are in radians */
+struct map_projection_reference_s {
+ double lat;
+ double lon;
+ double sin_lat;
+ double cos_lat;
+};
+
/**
* Initializes the map transformation.
*
@@ -74,7 +82,7 @@ struct crosstrack_error_s {
* @param lat in degrees (47.1234567°, not 471234567°)
* @param lon in degrees (8.1234567°, not 81234567°)
*/
-__EXPORT void map_projection_init(double lat_0, double lon_0);
+__EXPORT void map_projection_init(struct map_projection_reference_s *ref, double lat_0, double lon_0);
/**
* Transforms a point in the geographic coordinate system to the local azimuthal equidistant plane
@@ -83,7 +91,7 @@ __EXPORT void map_projection_init(double lat_0, double lon_0);
* @param lat in degrees (47.1234567°, not 471234567°)
* @param lon in degrees (8.1234567°, not 81234567°)
*/
-__EXPORT void map_projection_project(double lat, double lon, float *x, float *y);
+__EXPORT void map_projection_project(struct map_projection_reference_s *ref, double lat, double lon, float *x, float *y);
/**
* Transforms a point in the local azimuthal equidistant plane to the geographic coordinate system
@@ -93,7 +101,7 @@ __EXPORT void map_projection_project(double lat, double lon, float *x, float *y)
* @param lat in degrees (47.1234567°, not 471234567°)
* @param lon in degrees (8.1234567°, not 81234567°)
*/
-__EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon);
+__EXPORT void map_projection_reproject(struct map_projection_reference_s *ref, float x, float y, double *lat, double *lon);
/**
* Returns the distance to the next waypoint in meters.
@@ -115,30 +123,30 @@ __EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, dou
*/
__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
-__EXPORT void get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next, float* v_n, float* v_e);
+__EXPORT void get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n, float *v_e);
-__EXPORT void get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next, double lon_next, float* v_n, float* v_e);
+__EXPORT void get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n, float *v_e);
__EXPORT void add_vector_to_global_position(double lat_now, double lon_now, float v_n, float v_e, double *lat_res, double *lon_res);
-__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end);
+__EXPORT int get_distance_to_line(struct crosstrack_error_s *crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end);
-__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
- float radius, float arc_start_bearing, float arc_sweep);
+__EXPORT int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
+ float radius, float arc_start_bearing, float arc_sweep);
/*
* Calculate distance in global frame
*/
__EXPORT float get_distance_to_point_global_wgs84(double lat_now, double lon_now, float alt_now,
- double lat_next, double lon_next, float alt_next,
- float *dist_xy, float *dist_z);
+ double lat_next, double lon_next, float alt_next,
+ float *dist_xy, float *dist_z);
/*
* Calculate distance in local frame (NED)
*/
__EXPORT float mavlink_wpm_distance_to_point_local(float x_now, float y_now, float z_now,
- float x_next, float y_next, float z_next,
- float *dist_xy, float *dist_z);
+ float x_next, float y_next, float z_next,
+ float *dist_xy, float *dist_z);
__EXPORT float _wrap_180(float bearing);
__EXPORT float _wrap_360(float bearing);
diff --git a/src/lib/geo/geo_mag_declination.c b/src/lib/geo/geo_mag_declination.c
new file mode 100644
index 0000000000..09eac38f44
--- /dev/null
+++ b/src/lib/geo/geo_mag_declination.c
@@ -0,0 +1,136 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 MAV GEO Library (MAVGEO). All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name MAVGEO nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+* @file geo_mag_declination.c
+*
+* Calculation / lookup table for earth magnetic field declination.
+*
+* Lookup table from Scott Ferguson
+*
+* XXX Lookup table currently too coarse in resolution (only full degrees)
+* and lat/lon res - needs extension medium term.
+*
+*/
+
+#include