forked from Archive/PX4-Autopilot
Merge branch 'master' into acro2
This commit is contained in:
commit
b12928548c
|
@ -34,5 +34,8 @@ mavlink/include/mavlink/v0.9/
|
|||
/Documentation/html/
|
||||
/Documentation/doxygen*objdb*tmp
|
||||
.tags
|
||||
tags
|
||||
.tags_sorted_by_file
|
||||
.pydevproject
|
||||
.ropeproject
|
||||
*.orig
|
||||
|
|
|
@ -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 <http://unlicense.org/>
|
||||
|
||||
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=<something>" 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=<something>".
|
||||
# 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
|
||||
}
|
10
Debug/NuttX
10
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
|
||||
|
|
|
@ -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):
|
||||
|
|
Binary file not shown.
Binary file not shown.
|
@ -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
|
||||
}
|
|
@ -7,7 +7,7 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
echo "HIL Rascal 110 starting.."
|
||||
echo "X Plane HIL starting.."
|
||||
|
||||
set HIL yes
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -0,0 +1,35 @@
|
|||
#!nsh
|
||||
#
|
||||
# Steadidrone QU4D
|
||||
#
|
||||
# Thomas Gubler <thomasgubler@gmail.com>
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
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
|
|
@ -2,14 +2,14 @@
|
|||
#
|
||||
# UNTESTED UNTESTED!
|
||||
#
|
||||
# Generic 10” Hexa coaxial geometry
|
||||
# Generic 10" Hexa coaxial geometry
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
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
|
||||
|
|
|
@ -1,12 +1,12 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Octo coaxial geometry
|
||||
# Generic 10" Octo coaxial geometry
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER octo_cox
|
||||
set MIXER FMU_octo_cox
|
||||
|
||||
set PWM_OUTPUTS 12345678
|
||||
|
|
|
@ -5,4 +5,4 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER FMU_RET
|
||||
set MIXER easystar.mix
|
||||
|
|
|
@ -0,0 +1,5 @@
|
|||
#!nsh
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER FMU_AET
|
|
@ -2,9 +2,38 @@
|
|||
#
|
||||
# Phantom FPV Flying Wing
|
||||
#
|
||||
# Simon Wilks <sjwilks@gmail.com>
|
||||
# Simon Wilks <sjwilks@gmail.com>, Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -0,0 +1,42 @@
|
|||
#!nsh
|
||||
#
|
||||
# TBS Caipirinha Flying Wing
|
||||
#
|
||||
# Thomas Gubler <thomasgubler@gmail.com>
|
||||
#
|
||||
|
||||
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
|
|
@ -1,6 +1,6 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Quad X geometry
|
||||
# Generic 10" Quad X geometry
|
||||
#
|
||||
# Lorenz Meier <lm@inf.ethz.ch>
|
||||
#
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Quad + geometry
|
||||
# Generic 10" Quad + geometry
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Hexa X geometry
|
||||
# Generic 10" Hexa X geometry
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Hexa + geometry
|
||||
# Generic 10" Hexa + geometry
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Octo X geometry
|
||||
# Generic 10" Octo X geometry
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!nsh
|
||||
#
|
||||
# Generic 10” Octo + geometry
|
||||
# Generic 10" Octo + geometry
|
||||
#
|
||||
# Anton Babushkin <anton.babushkin@me.com>
|
||||
#
|
||||
|
|
|
@ -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
|
||||
#
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
#
|
||||
|
||||
attitude_estimator_ekf start
|
||||
#ekf_att_pos_estimator start
|
||||
position_estimator_inav start
|
||||
|
||||
mc_att_control start
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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
|
|
@ -0,0 +1,2 @@
|
|||
parameters.wiki
|
||||
parameters.xml
|
|
@ -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()
|
|
@ -16,5 +16,6 @@ astyle \
|
|||
--ignore-exclude-errors-x \
|
||||
--lineend=linux \
|
||||
--exclude=EASTL \
|
||||
--add-brackets \
|
||||
--add-brackets \
|
||||
--max-code-length=120 \
|
||||
$*
|
||||
|
|
|
@ -1,4 +0,0 @@
|
|||
parameters.wiki
|
||||
parameters.xml
|
||||
parameters.wikirpc.xml
|
||||
cookies.txt
|
|
@ -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
|
||||
|
|
|
@ -0,0 +1 @@
|
|||
__all__ = ["srcscanner", "srcparser", "xmlout", "dokuwikiout", "dokuwikirpc"]
|
|
@ -0,0 +1,44 @@
|
|||
from xml.sax.saxutils import escape
|
||||
import codecs
|
||||
|
||||
class DokuWikiTablesOutput():
|
||||
def __init__(self, groups):
|
||||
result = ("====== Parameter Reference ======\n"
|
||||
"<note>**This list is auto-generated from the source code** and contains the most recent parameter documentation.</note>\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 += "| ::: | <div>%s</div> ||||\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)
|
|
@ -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)
|
|
@ -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)
|
|
@ -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("""<?xml version='1.0'?>
|
||||
<methodCall>
|
||||
<methodName>wiki.putPage</methodName>
|
||||
<params>
|
||||
<param>
|
||||
<value>
|
||||
<string>:firmware:parameters</string>
|
||||
</value>
|
||||
</param>
|
||||
<param>
|
||||
<value>
|
||||
<string>""")
|
||||
f.write(escape(self.output))
|
||||
f.write("""</string>
|
||||
</value>
|
||||
</param>
|
||||
<param>
|
||||
<value>
|
||||
<name>sum</name>
|
||||
<string>Updated parameters automagically from code.</string>
|
||||
</value>
|
||||
</param>
|
||||
</params>
|
||||
</methodCall>""")
|
|
@ -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 = {
|
||||
|
|
|
@ -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)
|
||||
|
|
@ -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"
|
|
@ -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()
|
|
@ -0,0 +1,84 @@
|
|||
#!/usr/bin/env python
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2014 PX4 Development Team. All rights reserved.
|
||||
# Author: Julian Oes <joes@student.ethz.ch>
|
||||
|
||||
# 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()
|
|
@ -0,0 +1,2 @@
|
|||
# Remember to set the XMLRPCUSER and XMLRPCPASS environment variables
|
||||
python px_process_params.py --wiki-update
|
|
@ -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()
|
||||
|
||||
|
|
|
@ -1,2 +1,4 @@
|
|||
./obj/*
|
||||
mixer_test
|
||||
sbus2_test
|
||||
autodeclination_test
|
||||
|
|
|
@ -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)/*~
|
||||
rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~ mixer_test sbus2_test autodeclination_test
|
|
@ -0,0 +1,28 @@
|
|||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
#include <systemlib/mixer/mixer.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <px4iofirmware/px4io.h>
|
||||
#include "../../src/systemcmds/tests/tests.h"
|
||||
#include <geo/geo.h>
|
||||
|
||||
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);
|
||||
|
||||
}
|
|
@ -0,0 +1,5 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <systemlib/err.h>
|
||||
#define lowsyslog warnx
|
|
@ -11,4 +11,4 @@ int main(int argc, char *argv[]) {
|
|||
test_mixer(3, args);
|
||||
|
||||
test_conv(1, args);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -0,0 +1,6 @@
|
|||
#!/bin/sh
|
||||
|
||||
make clean
|
||||
make all
|
||||
./mixer_test
|
||||
./sbus2_test ../../../../data/sbus2/sbus2_r7008SB_gps_baro_tx_off.txt
|
|
@ -0,0 +1,75 @@
|
|||
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
#include <systemlib/mixer/mixer.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <px4iofirmware/px4io.h>
|
||||
#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);
|
||||
}
|
||||
|
||||
}
|
|
@ -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
|
|
@ -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 <command>.<priority>.<stacksize>.<entrypoint> 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)
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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)
|
||||
|
||||
|
|
|
@ -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)
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
}
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_compassmot_status_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_compassmot_status_send(MAVLINK_COMM_1 , packet1.throttle , packet1.current , packet1.interference , packet1.CompensationX , packet1.CompensationY , packet1.CompensationZ );
|
||||
mavlink_msg_compassmot_status_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_ahrs2(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
|
@ -1479,6 +1532,7 @@ static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id,
|
|||
mavlink_test_airspeed_autocal(system_id, component_id, last_msg);
|
||||
mavlink_test_rally_point(system_id, component_id, last_msg);
|
||||
mavlink_test_rally_fetch_point(system_id, component_id, last_msg);
|
||||
mavlink_test_compassmot_status(system_id, component_id, last_msg);
|
||||
mavlink_test_ahrs2(system_id, component_id, last_msg);
|
||||
}
|
||||
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Tue Feb 4 15:27:33 2014"
|
||||
#define MAVLINK_BUILD_DATE "Sun Apr 13 09:37:48 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue