diff --git a/.gitignore b/.gitignore
index 3fdc1bf2a2..3e94cf6205 100644
--- a/.gitignore
+++ b/.gitignore
@@ -19,12 +19,19 @@ Archives/*
Build/*
core
cscope.out
-dot.gdbinit
Firmware.sublime-workspace
Images/*.bin
Images/*.px4
mavlink/include/mavlink/v0.9/
+/nuttx-configs/px4io-v2/src/.depend
+/nuttx-configs/px4io-v2/src/Make.dep
+/nuttx-configs/px4io-v2/src/libboard.a
+/nuttx-configs/px4io-v1/src/.depend
+/nuttx-configs/px4io-v1/src/Make.dep
+/nuttx-configs/px4io-v1/src/libboard.a
/NuttX
/Documentation/doxy.log
/Documentation/html/
-/Documentation/doxygen*objdb*tmp
\ No newline at end of file
+/Documentation/doxygen*objdb*tmp
+.tags
+.tags_sorted_by_file
diff --git a/Debug/ARMv7M b/Debug/ARMv7M
index 803d964534..4c539b345d 100644
--- a/Debug/ARMv7M
+++ b/Debug/ARMv7M
@@ -56,7 +56,7 @@ define vecstate
if $mmfsr & (1<<3)
printf " during exception return"
end
- if $mmfsr & (1<<0)
+ if $mmfsr & (1<<1)
printf " during data access"
end
if $mmfsr & (1<<0)
diff --git a/Debug/Nuttx.py b/Debug/Nuttx.py
index b0864a2293..093edd0e09 100644
--- a/Debug/Nuttx.py
+++ b/Debug/Nuttx.py
@@ -2,6 +2,106 @@
import gdb, gdb.types
+class NX_register_set(object):
+ """Copy of the registers for a given context"""
+
+ v7_regmap = {
+ 'R13': 0,
+ 'SP': 0,
+ 'PRIORITY': 1,
+ 'R4': 2,
+ 'R5': 3,
+ 'R6': 4,
+ 'R7': 5,
+ 'R8': 6,
+ 'R9': 7,
+ 'R10': 8,
+ 'R11': 9,
+ 'EXC_RETURN': 10,
+ 'R0': 11,
+ 'R1': 12,
+ 'R2': 13,
+ 'R3': 14,
+ 'R12': 15,
+ 'R14': 16,
+ 'LR': 16,
+ 'R15': 17,
+ 'PC': 17,
+ 'XPSR': 18,
+ }
+
+ v7em_regmap = {
+ 'R13': 0,
+ 'SP': 0,
+ 'PRIORITY': 1,
+ 'R4': 2,
+ 'R5': 3,
+ 'R6': 4,
+ 'R7': 5,
+ 'R8': 6,
+ 'R9': 7,
+ 'R10': 8,
+ 'R11': 9,
+ 'EXC_RETURN': 10,
+ 'R0': 27,
+ 'R1': 28,
+ 'R2': 29,
+ 'R3': 30,
+ 'R12': 31,
+ 'R14': 32,
+ 'LR': 32,
+ 'R15': 33,
+ 'PC': 33,
+ 'XPSR': 34,
+ }
+
+ regs = dict()
+
+ def __init__(self, xcpt_regs):
+ if xcpt_regs is None:
+ self.regs['R0'] = long(gdb.parse_and_eval('$r0'))
+ self.regs['R1'] = long(gdb.parse_and_eval('$r1'))
+ self.regs['R2'] = long(gdb.parse_and_eval('$r2'))
+ self.regs['R3'] = long(gdb.parse_and_eval('$r3'))
+ self.regs['R4'] = long(gdb.parse_and_eval('$r4'))
+ self.regs['R5'] = long(gdb.parse_and_eval('$r5'))
+ self.regs['R6'] = long(gdb.parse_and_eval('$r6'))
+ self.regs['R7'] = long(gdb.parse_and_eval('$r7'))
+ self.regs['R8'] = long(gdb.parse_and_eval('$r8'))
+ self.regs['R9'] = long(gdb.parse_and_eval('$r9'))
+ self.regs['R10'] = long(gdb.parse_and_eval('$r10'))
+ self.regs['R11'] = long(gdb.parse_and_eval('$r11'))
+ self.regs['R12'] = long(gdb.parse_and_eval('$r12'))
+ self.regs['R13'] = long(gdb.parse_and_eval('$r13'))
+ self.regs['SP'] = long(gdb.parse_and_eval('$sp'))
+ self.regs['R14'] = long(gdb.parse_and_eval('$r14'))
+ self.regs['LR'] = long(gdb.parse_and_eval('$lr'))
+ self.regs['R15'] = long(gdb.parse_and_eval('$r15'))
+ self.regs['PC'] = long(gdb.parse_and_eval('$pc'))
+ self.regs['XPSR'] = long(gdb.parse_and_eval('$xpsr'))
+ else:
+ for key in self.v7em_regmap.keys():
+ self.regs[key] = int(xcpt_regs[self.v7em_regmap[key]])
+
+
+ @classmethod
+ def with_xcpt_regs(cls, xcpt_regs):
+ return cls(xcpt_regs)
+
+ @classmethod
+ def for_current(cls):
+ return cls(None)
+
+ def __format__(self, format_spec):
+ return format_spec.format(
+ registers = self.registers
+ )
+
+ @property
+ def registers(self):
+ return self.regs
+
+
class NX_task(object):
"""Reference to a NuttX task and methods for introspecting it"""
@@ -139,56 +239,12 @@ class NX_task(object):
if 'registers' not in self.__dict__:
registers = dict()
if self._state_is('TSTATE_TASK_RUNNING'):
- # XXX need to fix this to handle interrupt context
- registers['R0'] = long(gdb.parse_and_eval('$r0'))
- registers['R1'] = long(gdb.parse_and_eval('$r1'))
- registers['R2'] = long(gdb.parse_and_eval('$r2'))
- registers['R3'] = long(gdb.parse_and_eval('$r3'))
- registers['R4'] = long(gdb.parse_and_eval('$r4'))
- registers['R5'] = long(gdb.parse_and_eval('$r5'))
- registers['R6'] = long(gdb.parse_and_eval('$r6'))
- registers['R7'] = long(gdb.parse_and_eval('$r7'))
- registers['R8'] = long(gdb.parse_and_eval('$r8'))
- registers['R9'] = long(gdb.parse_and_eval('$r9'))
- registers['R10'] = long(gdb.parse_and_eval('$r10'))
- registers['R11'] = long(gdb.parse_and_eval('$r11'))
- registers['R12'] = long(gdb.parse_and_eval('$r12'))
- registers['R13'] = long(gdb.parse_and_eval('$r13'))
- registers['SP'] = long(gdb.parse_and_eval('$sp'))
- registers['R14'] = long(gdb.parse_and_eval('$r14'))
- registers['LR'] = long(gdb.parse_and_eval('$lr'))
- registers['R15'] = long(gdb.parse_and_eval('$r15'))
- registers['PC'] = long(gdb.parse_and_eval('$pc'))
- registers['XPSR'] = long(gdb.parse_and_eval('$xpsr'))
- # this would only be valid if we were in an interrupt
- registers['EXC_RETURN'] = 0
- # we should be able to get this...
- registers['PRIMASK'] = 0
+ registers = NX_register_set.for_current().registers
else:
context = self._tcb['xcp']
regs = context['regs']
- registers['R0'] = long(regs[27])
- registers['R1'] = long(regs[28])
- registers['R2'] = long(regs[29])
- registers['R3'] = long(regs[30])
- registers['R4'] = long(regs[2])
- registers['R5'] = long(regs[3])
- registers['R6'] = long(regs[4])
- registers['R7'] = long(regs[5])
- registers['R8'] = long(regs[6])
- registers['R9'] = long(regs[7])
- registers['R10'] = long(regs[8])
- registers['R11'] = long(regs[9])
- registers['R12'] = long(regs[31])
- registers['R13'] = long(regs[0])
- registers['SP'] = long(regs[0])
- registers['R14'] = long(regs[32])
- registers['LR'] = long(regs[32])
- registers['R15'] = long(regs[33])
- registers['PC'] = long(regs[33])
- registers['XPSR'] = long(regs[34])
- registers['EXC_RETURN'] = long(regs[10])
- registers['PRIMASK'] = long(regs[1])
+ registers = NX_register_set.with_xcpt_regs(regs).registers
+
self.__dict__['registers'] = registers
return self.__dict__['registers']
@@ -267,8 +323,7 @@ class NX_show_heap (gdb.Command):
def _print_allocations(self, region_start, region_end):
if region_start >= region_end:
- print 'heap region {} corrupt'.format(hex(region_start))
- return
+ raise gdb.GdbError('heap region {} corrupt'.format(hex(region_start)))
nodecount = region_end - region_start
print 'heap {} - {}'.format(region_start, region_end)
cursor = 1
@@ -286,13 +341,31 @@ class NX_show_heap (gdb.Command):
nregions = heap['mm_nregions']
region_starts = heap['mm_heapstart']
region_ends = heap['mm_heapend']
- print "{} heap(s)".format(nregions)
+ print '{} heap(s)'.format(nregions)
# walk the heaps
for i in range(0, nregions):
self._print_allocations(region_starts[i], region_ends[i])
NX_show_heap()
+class NX_show_interrupted_thread (gdb.Command):
+ """(NuttX) prints the register state of an interrupted thread when in interrupt/exception context"""
+ def __init__(self):
+ super(NX_show_interrupted_thread, self).__init__('show interrupted-thread', gdb.COMMAND_USER)
+ def invoke(self, args, from_tty):
+ regs = gdb.lookup_global_symbol('current_regs').value()
+ if regs is 0:
+ raise gdb.GdbError('not in interrupt context')
+ else:
+ registers = NX_register_set.with_xcpt_regs(regs)
+ my_fmt = ''
+ my_fmt += ' R0 {registers[R0]:#010x} {registers[R1]:#010x} {registers[R2]:#010x} {registers[R3]:#010x}\n'
+ my_fmt += ' R4 {registers[R4]:#010x} {registers[R5]:#010x} {registers[R6]:#010x} {registers[R7]:#010x}\n'
+ my_fmt += ' R8 {registers[R8]:#010x} {registers[R9]:#010x} {registers[R10]:#010x} {registers[R11]:#010x}\n'
+ my_fmt += ' R12 {registers[PC]:#010x}\n'
+ my_fmt += ' SP {registers[SP]:#010x} LR {registers[LR]:#010x} PC {registers[PC]:#010x} XPSR {registers[XPSR]:#010x}\n'
+ print format(registers, my_fmt)
+NX_show_interrupted_thread()
diff --git a/Debug/PX4 b/Debug/PX4
index 085cffe434..e99228ee0c 100644
--- a/Debug/PX4
+++ b/Debug/PX4
@@ -27,7 +27,7 @@ define _perf_print
# PC_COUNT
if $hdr->type == 0
set $count = (struct perf_ctr_count *)$hdr
- printf "%llu events,\n", $count->event_count;
+ printf "%llu events\n", $count->event_count
end
# PC_ELPASED
if $hdr->type == 1
diff --git a/Debug/dot.gdbinit b/Debug/dot.gdbinit
new file mode 100644
index 0000000000..d70410bc78
--- /dev/null
+++ b/Debug/dot.gdbinit
@@ -0,0 +1,13 @@
+# copy the file to .gdbinit in your Firmware tree, and adjust the path
+# below to match your system
+# For example:
+# target extended /dev/serial/by-id/usb-Black_Sphere_Technologies_Black_Magic_Probe_DDE5A1C4-if00
+# target extended /dev/ttyACM4
+
+
+monitor swdp_scan
+attach 1
+monitor vector_catch disable hard
+set mem inaccessible-by-default off
+set print pretty
+source Debug/PX4
diff --git a/Debug/olimex-px4fmu-debug.cfg b/Debug/olimex-px4fmu-debug.cfg
new file mode 100644
index 0000000000..61d70070db
--- /dev/null
+++ b/Debug/olimex-px4fmu-debug.cfg
@@ -0,0 +1,22 @@
+# program a bootable device load on a mavstation
+# To run type openocd -f mavprogram.cfg
+
+source [find interface/olimex-arm-usb-ocd-h.cfg]
+source [find px4fmu-v1-board.cfg]
+
+init
+halt
+
+# Find the flash inside this CPU
+flash probe 0
+
+# erase it (128 pages) then program and exit
+
+#flash erase_sector 0 0 127
+# stm32f1x mass_erase 0
+
+# It seems that Pat's image has a start address offset of 0x1000 but the vectors need to be at zero, so fixbin.sh moves things around
+#flash write_bank 0 fixed.bin 0
+#flash write_image firmware.elf
+#shutdown
+
diff --git a/Debug/openocd.gdbinit b/Debug/openocd.gdbinit
new file mode 100644
index 0000000000..92d78b58db
--- /dev/null
+++ b/Debug/openocd.gdbinit
@@ -0,0 +1,21 @@
+target remote :3333
+
+# Don't let GDB get confused while stepping
+define hook-step
+ mon cortex_m maskisr on
+end
+define hookpost-step
+ mon cortex_m maskisr off
+end
+
+mon init
+mon stm32_init
+# mon reset halt
+mon poll
+mon cortex_m maskisr auto
+set mem inaccessible-by-default off
+set print pretty
+source Debug/PX4
+
+echo PX4 resumed, press ctrl-c to interrupt\n
+continue
diff --git a/Debug/px4fmu-v1-board.cfg b/Debug/px4fmu-v1-board.cfg
new file mode 100644
index 0000000000..19b862a2d1
--- /dev/null
+++ b/Debug/px4fmu-v1-board.cfg
@@ -0,0 +1,38 @@
+# The latest defaults in OpenOCD 0.7.0 are actually prettymuch correct for the px4fmu
+
+# increase working area to 32KB for faster flash programming
+set WORKAREASIZE 0x8000
+
+source [find target/stm32f4x.cfg]
+
+# needed for px4
+reset_config trst_only
+
+proc stm32_reset {} {
+ reset halt
+# FIXME - needed to init periphs on reset
+# 0x40023800 RCC base
+# 0x24 RCC_APB2 0x75933
+# RCC_APB2 0
+}
+
+# perform init that is required on each connection to the target
+proc stm32_init {} {
+
+ # force jtag to not shutdown during sleep
+ #uint32_t cr = getreg32(STM32_DBGMCU_CR);
+ #cr |= DBGMCU_CR_STANDBY | DBGMCU_CR_STOP | DBGMCU_CR_SLEEP;
+ #putreg32(cr, STM32_DBGMCU_CR);
+ mww 0xe0042004 00000007
+}
+
+# if srst is not fitted use SYSRESETREQ to
+# perform a soft reset
+cortex_m reset_config sysresetreq
+
+# Let GDB directly program elf binaries
+gdb_memory_map enable
+
+# doesn't work yet
+gdb_flash_program disable
+
diff --git a/Debug/runopenocd.sh b/Debug/runopenocd.sh
new file mode 100755
index 0000000000..6258fccfb6
--- /dev/null
+++ b/Debug/runopenocd.sh
@@ -0,0 +1,5 @@
+#!/bin/bash
+
+DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
+
+openocd -f interface/olimex-arm-usb-ocd-h.cfg -f $DIR/px4fmu-v1-board.cfg
diff --git a/Debug/stm32f4x.cfg b/Debug/stm32f4x.cfg
deleted file mode 100644
index 28bfcfbbbc..0000000000
--- a/Debug/stm32f4x.cfg
+++ /dev/null
@@ -1,64 +0,0 @@
-# script for stm32f2xxx
-
-if { [info exists CHIPNAME] } {
- set _CHIPNAME $CHIPNAME
-} else {
- set _CHIPNAME stm32f4xxx
-}
-
-if { [info exists ENDIAN] } {
- set _ENDIAN $ENDIAN
-} else {
- set _ENDIAN little
-}
-
-# Work-area is a space in RAM used for flash programming
-# By default use 64kB
-if { [info exists WORKAREASIZE] } {
- set _WORKAREASIZE $WORKAREASIZE
-} else {
- set _WORKAREASIZE 0x10000
-}
-
-# JTAG speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so use F_JTAG = 1MHz
-#
-# Since we may be running of an RC oscilator, we crank down the speed a
-# bit more to be on the safe side. Perhaps superstition, but if are
-# running off a crystal, we can run closer to the limit. Note
-# that there can be a pretty wide band where things are more or less stable.
-jtag_khz 1000
-
-jtag_nsrst_delay 100
-jtag_ntrst_delay 100
-
-#jtag scan chain
-if { [info exists CPUTAPID ] } {
- set _CPUTAPID $CPUTAPID
-} else {
- # See STM Document RM0033
- # Section 32.6.3 - corresponds to Cortex-M3 r2p0
- set _CPUTAPID 0x4ba00477
-}
-jtag newtap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID
-
-if { [info exists BSTAPID ] } {
- set _BSTAPID $BSTAPID
-} else {
- # See STM Document RM0033
- # Section 32.6.2
- #
- set _BSTAPID 0x06413041
-}
-jtag newtap $_CHIPNAME bs -irlen 5 -expected-id $_BSTAPID
-
-set _TARGETNAME $_CHIPNAME.cpu
-target create $_TARGETNAME cortex_m3 -endian $_ENDIAN -chain-position $_TARGETNAME -rtos auto
-
-$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0
-
-set _FLASHNAME $_CHIPNAME.flash
-flash bank $_FLASHNAME stm32f2x 0 0 0 0 $_TARGETNAME
-
-# if srst is not fitted use SYSRESETREQ to
-# perform a soft reset
-cortex_m3 reset_config sysresetreq
diff --git a/Documentation/control_flow.graffle b/Documentation/control_flow.graffle
index 2535231108..6188c44308 100644
--- a/Documentation/control_flow.graffle
+++ b/Documentation/control_flow.graffle
@@ -5,7 +5,7 @@
ApplicationVersion
com.omnigroup.OmniGraffle
- 139.16.0.171715
+ 139.18.0.187838
CreationDate
2013-02-22 17:51:02 +0000
@@ -26,9 +26,9 @@
MasterSheets
ModificationDate
- 2013-04-20 15:38:47 +0000
+ 2013-08-25 05:58:40 +0000
Modifier
- Lorenz Meier
+ Lorenz
NotesVisible
NO
OriginVisible
@@ -55,7 +55,7 @@
NSPaperName
string
- iso-a3
+ BADB3137-012D-43BB-AFDE-2C0069A874AD
NSPaperSize
@@ -123,7 +123,7 @@
Bounds
- {{320.41170773935767, 646.55758982070449}, {100, 24}}
+ {{320.41170773792788, 646.55758667263535}, {100, 24}}
Class
ShapedGraphic
FitText
@@ -171,7 +171,7 @@
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -193,8 +193,8 @@
45
Points
- {283.47949897905681, 658.66217570036315}
- {459.99996984645378, 658.44980851233595}
+ {283.47949897630235, 658.66217426345122}
+ {459.99996984638915, 658.4498036008282}
Style
@@ -243,7 +243,7 @@
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -289,7 +289,7 @@
Pad
0
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;\red68\green147\blue53;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural
@@ -340,7 +340,7 @@
Pad
0
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;\red68\green147\blue53;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural
@@ -389,7 +389,7 @@
Pad
0
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;\red68\green147\blue53;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -437,7 +437,7 @@
Pad
0
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;\red68\green147\blue53;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -461,8 +461,8 @@
38
Points
- {584.52245687751122, 125.49999965650382}
- {584.56069426576869, 157.00000090441219}
+ {584.50076858662646, 125.50000000000021}
+ {584.50207726115275, 157.00000000001324}
Style
@@ -511,7 +511,7 @@
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -532,8 +532,8 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
34
Points
- {210.47275259888471, 495.87499981747118}
- {210.43193555768113, 543.06250166479344}
+ {210.49312053369275, 495.87499999999562}
+ {210.48281498396668, 543.06249999958038}
Style
@@ -582,7 +582,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -602,8 +602,8 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
32
Points
- {210.46968123779743, 580.06249992316259}
- {210.44442316539605, 627.25000030102035}
+ {210.47945786724097, 580.0625}
+ {210.47913680605853, 627.24999999999989}
Style
@@ -637,8 +637,8 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
30
Points
- {210.48620562018775, 690.25}
- {210.49612530146715, 737.4375}
+ {210.48620103078346, 690.25}
+ {210.49611383706232, 737.4375}
Style
@@ -694,7 +694,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -731,7 +731,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -789,7 +789,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -801,7 +801,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Bounds
- {{152.49994329565658, 397.00120984204113}, {116, 24}}
+ {{152.49998995675264, 397.00120984204113}, {116, 24}}
Class
ShapedGraphic
FitText
@@ -849,7 +849,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -877,8 +877,8 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
-1
Points
- {584.49994992834695, 220}
- {584.4997453697481, 348.6875000000008}
+ {584.49999370649277, 220}
+ {584.49999370649277, 348.6875}
Style
@@ -971,7 +971,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -991,8 +991,8 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
17
Points
- {210.49997491180866, 385.6875}
- {210.49991091996927, 432.875}
+ {210.49998995675264, 385.6875}
+ {210.49998995675264, 432.875}
Style
@@ -1029,7 +1029,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Points
{283.49999999999511, 270.00001907176534}
- {339.50000000000028, 270.00001907176534}
+ {339.49999999999994, 270.00001907176534}
Style
@@ -1098,8 +1098,8 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
13
Points
- {210.49171354592596, 207}
- {210.49498558851923, 238.4999999999998}
+ {210.49209551674531, 207}
+ {210.49601794208507, 238.5}
Style
@@ -1133,8 +1133,8 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
12
Points
- {210.49498558851246, 138.5000000000002}
- {210.48997117702493, 170.00000000001342}
+ {210.49601794208485, 138.5}
+ {210.49203588416967, 170}
Style
@@ -1190,7 +1190,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -1234,7 +1234,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -1278,7 +1278,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -1322,7 +1322,7 @@ VEHICLE_LOCAL_POSITION_SETPOINT}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -1360,7 +1360,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -1395,7 +1395,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -1430,7 +1430,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -1675,7 +1675,7 @@ PX4IO or PX4FMU}
Pad
0
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -1774,7 +1774,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -2145,7 +2145,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -2536,7 +2536,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -2927,7 +2927,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -3361,7 +3361,7 @@ PX4IO or PX4FMU}
Pad
0
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -3404,7 +3404,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -3791,7 +3791,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -4178,7 +4178,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -4565,7 +4565,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -4963,7 +4963,7 @@ PX4IO or PX4FMU}
Pad
0
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -5062,7 +5062,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -5421,7 +5421,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -5780,7 +5780,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -6175,7 +6175,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -6660,7 +6660,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -7019,7 +7019,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -7406,7 +7406,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -7793,7 +7793,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -8300,7 +8300,7 @@ PX4IO or PX4FMU}
Pad
0
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -8404,7 +8404,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -8795,7 +8795,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -9166,7 +9166,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -9537,7 +9537,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -9928,7 +9928,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -10367,7 +10367,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -10779,7 +10779,7 @@ PX4IO or PX4FMU}
Pad
0
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -10883,7 +10883,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -11270,7 +11270,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -11629,7 +11629,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -11988,7 +11988,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -12375,7 +12375,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -12810,7 +12810,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -13257,6 +13257,1697 @@ PX4IO or PX4FMU}
1 0/72 in = 1.0000 in
GraphicsList
+
+ Class
+ Group
+ Graphics
+
+
+ Bounds
+ {{281.4621559838219, 891.87422762618871}, {48, 14}}
+ Class
+ ShapedGraphic
+ FitText
+ YES
+ Flow
+ Resize
+ ID
+ 1534
+ Shape
+ Rectangle
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+ stroke
+
+ Draws
+ NO
+
+
+ Text
+
+ Pad
+ 0
+ Text
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\b\fs24 \cf0 QUAD
+\b0 H}
+ VerticalPad
+ 0
+
+ Wrap
+ NO
+
+
+ Class
+ Group
+ Graphics
+
+
+ Bounds
+ {{282.10284531231378, 729.4992324185539}, {50.666667938232422, 36}}
+ Class
+ ShapedGraphic
+ ID
+ 1536
+ Rotation
+ 270
+ Shape
+ HorizontalTriangle
+ Style
+
+ fill
+
+ Color
+
+ b
+ 0.13195
+ g
+ 0.165669
+ r
+ 1
+
+
+
+ Text
+
+ VerticalPad
+ 0
+
+
+
+ Bounds
+ {{271.43617794923421, 713.47324050519865}, {72, 72}}
+ Class
+ ShapedGraphic
+ ID
+ 1537
+ Shape
+ Rectangle
+ Style
+
+ stroke
+
+ CornerRadius
+ 9
+
+
+
+
+ ID
+ 1535
+ Rotation
+ 315
+
+
+ Class
+ Group
+ Graphics
+
+
+ Bounds
+ {{387.95096684220994, 833.99511602139876}, {24, 24}}
+ Class
+ ShapedGraphic
+ ID
+ 1539
+ Shape
+ Circle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ Text
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 4}
+ VerticalPad
+ 0
+
+
+
+ Class
+ Group
+ Graphics
+
+
+ Class
+ LineGraphic
+ ID
+ 1541
+ Points
+
+ {447.56635253821332, 822.0678021003348}
+ {445.35664384700522, 823.21685061976291}
+
+ Style
+
+ stroke
+
+ HeadArrow
+ 0
+ Legacy
+
+ TailArrow
+ 0
+
+
+
+
+ Bounds
+ {{359.66328626413321, 875.75030562593793}, {16, 18.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1542
+ Rotation
+ 45
+ Shape
+ HorizontalTriangle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+
+
+ Bounds
+ {{349.2634215034181, 795.53620935597417}, {101.5, 101.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1543
+ Rotation
+ 135
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+
+
+ Bounds
+ {{346.5134215034181, 792.78620935597417}, {107, 107}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1544
+ Rotation
+ 135
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+
+
+ ID
+ 1540
+ Rotation
+ 315
+
+
+ Class
+ Group
+ Graphics
+
+
+ Class
+ LineGraphic
+ ID
+ 1546
+ Points
+
+ {352.51941963025371, 870.09214125245364}
+ {354.7291283214617, 868.94309273302531}
+
+ Style
+
+ stroke
+
+ HeadArrow
+ 0
+ Legacy
+
+ TailArrow
+ 0
+
+
+
+
+ Bounds
+ {{424.42248590433371, 797.90963772685075}, {16, 18.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1547
+ Rotation
+ 225
+ Shape
+ HorizontalTriangle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+
+
+ Bounds
+ {{349.32235066504887, 795.12373399681428}, {101.5, 101.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1548
+ Rotation
+ 315
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+
+
+ Bounds
+ {{346.57235066504887, 792.37373399681428}, {107, 107}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1549
+ Rotation
+ 315
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+
+
+ ID
+ 1545
+ Rotation
+ 315
+
+
+ Bounds
+ {{349.03928365032027, 795.08342417943641}, {101.82337649086284, 101.82337649086284}}
+ Class
+ ShapedGraphic
+ ID
+ 1550
+ Rotation
+ 315
+ Shape
+ Circle
+ Style
+
+ fill
+
+ Color
+
+ a
+ 0.78
+ b
+ 0.234512
+ g
+ 0.673128
+ r
+ 0.148947
+
+
+ shadow
+
+ Draws
+ NO
+
+ stroke
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+
+
+ ID
+ 1538
+ Rotation
+ 315
+
+
+ Class
+ Group
+ Graphics
+
+
+ Bounds
+ {{202.98738428569231, 833.92908910567212}, {24, 24}}
+ Class
+ ShapedGraphic
+ ID
+ 1552
+ Shape
+ Circle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ Text
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 2}
+ VerticalPad
+ 0
+
+ VFlip
+ YES
+
+
+ Class
+ Group
+ Graphics
+
+
+ Class
+ LineGraphic
+ ID
+ 1554
+ Points
+
+ {167.72554658547227, 821.64822718882488}
+ {169.93525527668044, 822.79727570825287}
+
+ Style
+
+ stroke
+
+ HeadArrow
+ 0
+ Legacy
+
+ TailArrow
+ 0
+
+
+
+
+ Bounds
+ {{239.62861285955245, 875.33073071442777}, {16, 18.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1555
+ Rotation
+ 135
+ Shape
+ HorizontalTriangle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ VFlip
+ YES
+
+
+ Bounds
+ {{164.52847762026795, 795.1166344444639}, {101.5, 101.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1556
+ Rotation
+ 45
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+ VFlip
+ YES
+
+
+ Bounds
+ {{161.77847762026795, 792.3666344444639}, {107, 107}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1557
+ Rotation
+ 45
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+ VFlip
+ YES
+
+
+ ID
+ 1553
+ Rotation
+ 225
+ VFlip
+ YES
+
+
+ Class
+ Group
+ Graphics
+
+
+ Class
+ LineGraphic
+ ID
+ 1559
+ Points
+
+ {262.41893329590295, 870.02611253847215}
+ {260.20922460469507, 868.87706401904404}
+
+ Style
+
+ stroke
+
+ HeadArrow
+ 0
+ Legacy
+
+ TailArrow
+ 0
+
+
+
+
+ Bounds
+ {{174.51586702182317, 797.84360901286959}, {16, 18.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1560
+ Rotation
+ 315
+ Shape
+ HorizontalTriangle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ VFlip
+ YES
+
+
+ Bounds
+ {{164.11600226110755, 795.05770528283301}, {101.5, 101.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1561
+ Rotation
+ 225
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+ VFlip
+ YES
+
+
+ Bounds
+ {{161.36600226110755, 792.30770528283301}, {107, 107}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1562
+ Rotation
+ 225
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+ VFlip
+ YES
+
+
+ ID
+ 1558
+ Rotation
+ 225
+ VFlip
+ YES
+
+
+ Bounds
+ {{164.07569244372991, 795.01739580669891}, {101.82337649086284, 101.82337649086284}}
+ Class
+ ShapedGraphic
+ ID
+ 1563
+ Rotation
+ 225
+ Shape
+ Circle
+ Style
+
+ fill
+
+ Color
+
+ a
+ 0.78
+ b
+ 0.673128
+ g
+ 0.534129
+ r
+ 0.217952
+
+
+ shadow
+
+ Draws
+ NO
+
+ stroke
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ VFlip
+ YES
+
+
+ ID
+ 1551
+ Rotation
+ 315
+
+
+ Class
+ Group
+ Graphics
+
+
+ Bounds
+ {{424.02444829866442, 666.20122319568361}, {24, 24}}
+ Class
+ ShapedGraphic
+ ID
+ 1565
+ Shape
+ Circle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ Text
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 1}
+ VerticalPad
+ 0
+
+ VFlip
+ YES
+
+
+ Class
+ Group
+ Graphics
+
+
+ Class
+ LineGraphic
+ ID
+ 1567
+ Points
+
+ {388.76261059844421, 653.92036127883637}
+ {390.97231928965209, 655.06940979826459}
+
+ Style
+
+ stroke
+
+ HeadArrow
+ 0
+ Legacy
+
+ TailArrow
+ 0
+
+
+
+
+ Bounds
+ {{460.66567687252439, 707.60286480443915}, {16, 18.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1568
+ Rotation
+ 135
+ Shape
+ HorizontalTriangle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ VFlip
+ YES
+
+
+ Bounds
+ {{385.56554163323983, 627.3887685344755}, {101.5, 101.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1569
+ Rotation
+ 45
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+ VFlip
+ YES
+
+
+ Bounds
+ {{382.81554163323983, 624.6387685344755}, {107, 107}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1570
+ Rotation
+ 45
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+ VFlip
+ YES
+
+
+ ID
+ 1566
+ Rotation
+ 225
+ VFlip
+ YES
+
+
+ Class
+ Group
+ Graphics
+
+
+ Class
+ LineGraphic
+ ID
+ 1572
+ Points
+
+ {483.455997308875, 702.29824662848364}
+ {481.24628861766723, 701.14919810905553}
+
+ Style
+
+ stroke
+
+ HeadArrow
+ 0
+ Legacy
+
+ TailArrow
+ 0
+
+
+
+
+ Bounds
+ {{395.55293103479517, 630.11574310288108}, {16, 18.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1573
+ Rotation
+ 315
+ Shape
+ HorizontalTriangle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ VFlip
+ YES
+
+
+ Bounds
+ {{385.15306627407972, 627.32983937284462}, {101.5, 101.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1574
+ Rotation
+ 225
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+ VFlip
+ YES
+
+
+ Bounds
+ {{382.40306627407972, 624.57983937284462}, {107, 107}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1575
+ Rotation
+ 225
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+ VFlip
+ YES
+
+
+ ID
+ 1571
+ Rotation
+ 225
+ VFlip
+ YES
+
+
+ Bounds
+ {{385.11275645670196, 627.28952989671052}, {101.82337649086284, 101.82337649086284}}
+ Class
+ ShapedGraphic
+ ID
+ 1576
+ Rotation
+ 225
+ Shape
+ Circle
+ Style
+
+ fill
+
+ Color
+
+ a
+ 0.78
+ b
+ 0.673128
+ g
+ 0.534129
+ r
+ 0.217952
+
+
+ shadow
+
+ Draws
+ NO
+
+ stroke
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ VFlip
+ YES
+
+
+ ID
+ 1564
+ Rotation
+ 315
+
+
+ Class
+ Group
+ Graphics
+
+
+ Bounds
+ {{170.01738471163631, 670.02445557113811}, {24, 24}}
+ Class
+ ShapedGraphic
+ ID
+ 1578
+ Shape
+ Circle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ Text
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 3}
+ VerticalPad
+ 0
+
+
+
+ Class
+ Group
+ Graphics
+
+
+ Class
+ LineGraphic
+ ID
+ 1580
+ Points
+
+ {229.63277040763995, 658.09714165007426}
+ {227.42306171643185, 659.24619016950237}
+
+ Style
+
+ stroke
+
+ HeadArrow
+ 0
+ Legacy
+
+ TailArrow
+ 0
+
+
+
+
+ Bounds
+ {{141.72970413355978, 711.77964517567739}, {16, 18.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1581
+ Rotation
+ 45
+ Shape
+ HorizontalTriangle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+
+
+ Bounds
+ {{131.32983937284456, 631.5655489057134}, {101.5, 101.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1582
+ Rotation
+ 135
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+
+
+ Bounds
+ {{128.57983937284456, 628.8155489057134}, {107, 107}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1583
+ Rotation
+ 135
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+
+
+ ID
+ 1579
+ Rotation
+ 315
+
+
+ Class
+ Group
+ Graphics
+
+
+ Class
+ LineGraphic
+ ID
+ 1585
+ Points
+
+ {134.58583749968011, 706.12148080219276}
+ {136.79554619088805, 704.97243228276466}
+
+ Style
+
+ stroke
+
+ HeadArrow
+ 0
+ Legacy
+
+ TailArrow
+ 0
+
+
+
+
+ Bounds
+ {{206.48890377375986, 633.93897727658998}, {16, 18.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1586
+ Rotation
+ 225
+ Shape
+ HorizontalTriangle
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+
+
+ Bounds
+ {{131.38876853447516, 631.15307354655363}, {101.5, 101.5}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1587
+ Rotation
+ 315
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+
+
+ Bounds
+ {{128.63876853447516, 628.40307354655363}, {107, 107}}
+ Class
+ ShapedGraphic
+ HFlip
+ YES
+ ID
+ 1588
+ Rotation
+ 315
+ Shape
+ AdjustableArc
+ ShapeData
+
+ endAngle
+ 72
+ startAngle
+ 281
+
+ Style
+
+ fill
+
+ Draws
+ NO
+
+ shadow
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+ TextRelativeArea
+ {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}}
+
+
+ ID
+ 1584
+ Rotation
+ 315
+
+
+ Bounds
+ {{131.1057015197467, 631.11276372917564}, {101.82337649086284, 101.82337649086284}}
+ Class
+ ShapedGraphic
+ ID
+ 1589
+ Rotation
+ 315
+ Shape
+ Circle
+ Style
+
+ fill
+
+ Color
+
+ a
+ 0.78
+ b
+ 0.234512
+ g
+ 0.673128
+ r
+ 0.148947
+
+
+ shadow
+
+ Draws
+ NO
+
+ stroke
+
+ Draws
+ NO
+
+
+ Text
+
+ VerticalPad
+ 0
+
+
+
+ ID
+ 1577
+ Rotation
+ 315
+
+
+ Bounds
+ {{253.2315878349163, 736.67782196944336}, {8, 134}}
+ Class
+ ShapedGraphic
+ ID
+ 1590
+ Rotation
+ 225
+ Shape
+ Rectangle
+
+
+ Bounds
+ {{371.51084102985902, 644.26864825135988}, {8, 134}}
+ Class
+ ShapedGraphic
+ ID
+ 1591
+ Rotation
+ 240
+ Shape
+ Rectangle
+
+
+ Bounds
+ {{353.64074716687509, 736.67780398678804}, {8, 134}}
+ Class
+ ShapedGraphic
+ ID
+ 1592
+ Rotation
+ 315
+ Shape
+ Rectangle
+
+
+ Bounds
+ {{234.00404905414581, 645.26862880510475}, {8, 134}}
+ Class
+ ShapedGraphic
+ ID
+ 1593
+ Rotation
+ 300
+ Shape
+ Rectangle
+
+
+ ID
+ 1533
+
Class
Group
@@ -13353,7 +15044,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -13744,7 +15435,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -14135,7 +15826,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -14526,7 +16217,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -14928,7 +16619,7 @@ PX4IO or PX4FMU}
Pad
0
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -14966,7 +16657,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -15337,7 +17028,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -15708,7 +17399,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -16115,7 +17806,7 @@ PX4IO or PX4FMU}
Text
Text
- {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+ {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf390
\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
{\colortbl;\red255\green255\blue255;}
\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
@@ -16581,6 +18272,94 @@ PX4IO or PX4FMU}
VPages
1
+
+ ActiveLayerIndex
+ 0
+ AutoAdjust
+
+ BackgroundGraphic
+
+ Bounds
+ {{0, 0}, {806, 1132}}
+ Class
+ SolidGraphic
+ ID
+ 2
+ Style
+
+ shadow
+
+ Draws
+ NO
+
+ stroke
+
+ Draws
+ NO
+
+
+
+ BaseZoom
+ 0
+ CanvasOrigin
+ {0, 0}
+ ColumnAlign
+ 1
+ ColumnSpacing
+ 36
+ DisplayScale
+ 1 0/72 in = 1.0000 in
+ GraphicsList
+
+ GridInfo
+
+ HPages
+ 1
+ KeepToScale
+
+ Layers
+
+
+ Lock
+ NO
+ Name
+ Ebene 1
+ Print
+ YES
+ View
+ YES
+
+
+ LayoutInfo
+
+ Animate
+ NO
+ circoMinDist
+ 18
+ circoSeparation
+ 0.0
+ layoutEngine
+ dot
+ neatoSeparation
+ 0.0
+ twopiSeparation
+ 0.0
+
+ Orientation
+ 2
+ PrintOnePage
+
+ RowAlign
+ 1
+ RowSpacing
+ 36
+ SheetTitle
+ Arbeitsfläche 6
+ UniqueID
+ 6
+ VPages
+ 1
+
SmartAlignmentGuidesActive
YES
@@ -16600,7 +18379,7 @@ PX4IO or PX4FMU}
Frame
- {{96, 56}, {1043, 822}}
+ {{170, 4}, {1043, 774}}
ListView
OutlineWidth
@@ -16614,7 +18393,7 @@ PX4IO or PX4FMU}
SidebarWidth
120
VisibleRegion
- {{-51, -33}, {908, 683}}
+ {{-51, 366}, {908, 635}}
Zoom
1
ZoomValues
@@ -16644,6 +18423,11 @@ PX4IO or PX4FMU}
1
1
+
+ Arbeitsfläche 6
+ 1
+ 1
+
diff --git a/Documentation/fixed_wing_control.odg b/Documentation/fixed_wing_control.odg
new file mode 100644
index 0000000000..0918edcac8
Binary files /dev/null and b/Documentation/fixed_wing_control.odg differ
diff --git a/Documentation/flight_mode_state_machine.pdf b/Documentation/flight_mode_state_machine.pdf
index cd234ada73..af41953eec 100644
Binary files a/Documentation/flight_mode_state_machine.pdf and b/Documentation/flight_mode_state_machine.pdf differ
diff --git a/Documentation/rc_mode_switch.odg b/Documentation/rc_mode_switch.odg
index a8a6f93f31..29d738c39c 100644
Binary files a/Documentation/rc_mode_switch.odg and b/Documentation/rc_mode_switch.odg differ
diff --git a/Documentation/rc_mode_switch.pdf b/Documentation/rc_mode_switch.pdf
index 3141eed7ff..856dd55c59 100644
Binary files a/Documentation/rc_mode_switch.pdf and b/Documentation/rc_mode_switch.pdf differ
diff --git a/Images/px4fmu-v2.prototype b/Images/px4fmu-v2.prototype
new file mode 100644
index 0000000000..5109b77d1e
--- /dev/null
+++ b/Images/px4fmu-v2.prototype
@@ -0,0 +1,12 @@
+{
+ "board_id": 9,
+ "magic": "PX4FWv1",
+ "description": "Firmware for the PX4FMUv2 board",
+ "image": "",
+ "build_time": 0,
+ "summary": "PX4FMUv2",
+ "version": "0.1",
+ "image_size": 0,
+ "git_identity": "",
+ "board_revision": 0
+}
diff --git a/Images/px4io-v2.prototype b/Images/px4io-v2.prototype
new file mode 100644
index 0000000000..af87924e90
--- /dev/null
+++ b/Images/px4io-v2.prototype
@@ -0,0 +1,12 @@
+{
+ "board_id": 10,
+ "magic": "PX4FWv2",
+ "description": "Firmware for the PX4IOv2 board",
+ "image": "",
+ "build_time": 0,
+ "summary": "PX4IOv2",
+ "version": "2.0",
+ "image_size": 0,
+ "git_identity": "",
+ "board_revision": 0
+}
diff --git a/Images/px4iov2.prototype b/Images/px4iov2.prototype
new file mode 100644
index 0000000000..af87924e90
--- /dev/null
+++ b/Images/px4iov2.prototype
@@ -0,0 +1,12 @@
+{
+ "board_id": 10,
+ "magic": "PX4FWv2",
+ "description": "Firmware for the PX4IOv2 board",
+ "image": "",
+ "build_time": 0,
+ "summary": "PX4IOv2",
+ "version": "2.0",
+ "image_size": 0,
+ "git_identity": "",
+ "board_revision": 0
+}
diff --git a/Makefile b/Makefile
index 778395cee9..0a85622512 100644
--- a/Makefile
+++ b/Makefile
@@ -40,14 +40,27 @@ export PX4_BASE := $(realpath $(dir $(lastword $(MAKEFILE_LIST))))/
include $(PX4_BASE)makefiles/setup.mk
#
-# Canned firmware configurations that we build.
+# Get a version string provided by git
+# This assumes that git command is available and that
+# the directory holding this file also contains .git directory
#
-CONFIGS ?= $(subst config_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)config_*.mk))))
+GIT_DESC := $(shell git log -1 --pretty=format:%H)
+ifneq ($(words $(GIT_DESC)),1)
+ GIT_DESC := "unknown_git_version"
+endif
+export GIT_DESC
#
-# Boards that we build NuttX export kits for.
+# Canned firmware configurations that we (know how to) build.
#
-BOARDS := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)board_*.mk))))
+KNOWN_CONFIGS := $(subst config_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)config_*.mk))))
+CONFIGS ?= $(KNOWN_CONFIGS)
+
+#
+# Boards that we (know how to) build NuttX export kits for.
+#
+KNOWN_BOARDS := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)board_*.mk))))
+BOARDS ?= $(KNOWN_BOARDS)
#
# Debugging
@@ -87,10 +100,11 @@ endif
#
# Built products
#
-STAGED_FIRMWARES = $(foreach config,$(CONFIGS),$(IMAGE_DIR)$(config).px4)
-FIRMWARES = $(foreach config,$(CONFIGS),$(BUILD_DIR)$(config).build/firmware.px4)
+DESIRED_FIRMWARES = $(foreach config,$(CONFIGS),$(IMAGE_DIR)$(config).px4)
+STAGED_FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(IMAGE_DIR)$(config).px4)
+FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(BUILD_DIR)$(config).build/firmware.px4)
-all: $(STAGED_FIRMWARES)
+all: $(DESIRED_FIRMWARES)
#
# Copy FIRMWARES into the image directory.
@@ -114,13 +128,26 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
@$(ECHO) %%%%
@$(ECHO) %%%% Building $(config) in $(work_dir)
@$(ECHO) %%%%
- $(Q) mkdir -p $(work_dir)
- $(Q) make -r -C $(work_dir) \
+ $(Q) $(MKDIR) -p $(work_dir)
+ $(Q) $(MAKE) -r -C $(work_dir) \
-f $(PX4_MK_DIR)firmware.mk \
CONFIG=$(config) \
WORK_DIR=$(work_dir) \
$(FIRMWARE_GOAL)
+#
+# Make FMU firmwares depend on the corresponding IO firmware.
+#
+# This is a pretty vile hack, since it hard-codes knowledge of the FMU->IO dependency
+# and forces the _default config in all cases. There has to be a better way to do this...
+#
+FMU_VERSION = $(patsubst px4fmu-%,%,$(word 1, $(subst _, ,$(1))))
+define FMU_DEP
+$(BUILD_DIR)$(1).build/firmware.px4: $(IMAGE_DIR)px4io-$(call FMU_VERSION,$(1))_default.px4
+endef
+FMU_CONFIGS := $(filter px4fmu%,$(CONFIGS))
+$(foreach config,$(FMU_CONFIGS),$(eval $(call FMU_DEP,$(config))))
+
#
# Build the NuttX export archives.
#
@@ -147,12 +174,12 @@ $(ARCHIVE_DIR)%.export: configuration = nsh
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC)
@$(ECHO) %% Configuring NuttX for $(board)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
- $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
@$(ECHO) %% Exporting NuttX for $(board)
- $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
- $(Q) mkdir -p $(dir $@)
+ $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
+ $(Q) $(MKDIR) -p $(dir $@)
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
$(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board))
@@ -168,11 +195,11 @@ BOARD = $(BOARDS)
menuconfig: $(NUTTX_SRC)
@$(ECHO) %% Configuring NuttX for $(BOARD)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
- $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
$(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(BOARD) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(BOARD)/nsh)
@$(ECHO) %% Running menuconfig for $(BOARD)
- $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig
+ $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig
@$(ECHO) %% Saving configuration file
$(Q)$(COPY) $(NUTTX_SRC).config $(PX4_BASE)nuttx-configs/$(BOARD)/nsh/defconfig
else
@@ -191,7 +218,7 @@ $(NUTTX_SRC):
# Testing targets
#
testbuild:
- $(Q) (cd $(PX4_BASE) && make distclean && make archives && make -j8)
+ $(Q) (cd $(PX4_BASE) && $(MAKE) distclean && $(MAKE) archives && $(MAKE) -j8)
#
# Cleanup targets. 'clean' should remove all built products and force
@@ -206,7 +233,8 @@ clean:
.PHONY: distclean
distclean: clean
$(Q) $(REMOVE) $(ARCHIVE_DIR)*.export
- $(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) $(MAKE) -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) (cd $(NUTTX_SRC)/configs && $(FIND) . -maxdepth 1 -type l -delete)
#
# Print some help text
@@ -228,9 +256,9 @@ help:
@$(ECHO) " A limited set of configs can be built with CONFIGS="
@$(ECHO) ""
@for config in $(CONFIGS); do \
- echo " $$config"; \
- echo " Build just the $$config firmware configuration."; \
- echo ""; \
+ $(ECHO) " $$config"; \
+ $(ECHO) " Build just the $$config firmware configuration."; \
+ $(ECHO) ""; \
done
@$(ECHO) " clean"
@$(ECHO) " Remove all firmware build pieces."
diff --git a/ROMFS/px4fmu_common/init.d/01_fmu_quad_x b/ROMFS/px4fmu_common/init.d/01_fmu_quad_x
deleted file mode 100644
index 58a970eba5..0000000000
--- a/ROMFS/px4fmu_common/init.d/01_fmu_quad_x
+++ /dev/null
@@ -1,107 +0,0 @@
-#!nsh
-#
-# Flight startup script for PX4FMU with PWM outputs.
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-echo "[init] doing PX4FMU Quad startup..."
-
-#
-# Start the ORB
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set MC_ATTRATE_P 0.14
- param set MC_ATTRATE_I 0
- param set MC_ATTRATE_D 0.006
- param set MC_ATT_P 5.5
- param set MC_ATT_I 0
- param set MC_ATT_D 0
- param set MC_YAWPOS_D 0
- param set MC_YAWPOS_I 0
- param set MC_YAWPOS_P 0.6
- param set MC_YAWRATE_D 0
- param set MC_YAWRATE_I 0
- param set MC_YAWRATE_P 0.08
- param set RC_SCALE_PITCH 1
- param set RC_SCALE_ROLL 1
- param set RC_SCALE_YAW 3
-
- param set SYS_AUTOCONFIG 0
- param save /fs/microsd/params
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
-#
-param set MAV_TYPE 2
-
-#
-# Start MAVLink
-#
-mavlink start -d /dev/ttyS0 -b 57600
-usleep 5000
-
-#
-# Start the sensors and test them.
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start the commander.
-#
-commander start
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator
-#
-attitude_estimator_ekf start
-
-echo "[init] starting PWM output"
-fmu mode_pwm
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-pwm -u 400 -m 0xff
-
-#
-# Start attitude control
-#
-multirotor_att_control start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
diff --git a/ROMFS/px4fmu_common/init.d/02_io_quad_x b/ROMFS/px4fmu_common/init.d/02_io_quad_x
deleted file mode 100644
index c63e92f6d3..0000000000
--- a/ROMFS/px4fmu_common/init.d/02_io_quad_x
+++ /dev/null
@@ -1,101 +0,0 @@
-#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
- param save /fs/microsd/params
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
-#
-param set MAV_TYPE 2
-
-#
-# Start MAVLink (depends on orb)
-#
-mavlink start -d /dev/ttyS1 -b 57600
-usleep 5000
-
-#
-# Start the commander (depends on orb, mavlink)
-#
-commander start
-
-#
-# Start PX4IO interface (depends on orb, commander)
-#
-px4io start
-
-#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
-
-#
-# Disable px4io topic limiting
-#
-px4io limit 200
-
-#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator (depends on orb)
-#
-attitude_estimator_ekf start
-
-#
-# Load mixer and start controllers (depends on px4io)
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-pwm -u 400 -m 0xff
-multirotor_att_control start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
diff --git a/ROMFS/px4fmu_common/init.d/08_ardrone b/ROMFS/px4fmu_common/init.d/08_ardrone
index f55ac2ae34..f6f09ac220 100644
--- a/ROMFS/px4fmu_common/init.d/08_ardrone
+++ b/ROMFS/px4fmu_common/init.d/08_ardrone
@@ -1,99 +1,57 @@
#!nsh
-#
-# Flight startup script for PX4FMU on PX4IOAR carrier board.
-#
-# Disable the USB interface
-set USB no
-
-# Disable autostarting other apps
-set MODE ardrone
-
-echo "[init] doing PX4IOAR startup..."
+echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
#
-# Start the ORB
+# Load default params for this platform
#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
+if param compare SYS_AUTOCONFIG 1
then
- param load /fs/microsd/params
+ # Set all params here, then disable autoconfig
+ param set MC_ATTRATE_D 0
+ param set MC_ATTRATE_I 0
+ param set MC_ATTRATE_P 0.13
+ param set MC_ATT_D 0
+ param set MC_ATT_I 0.3
+ param set MC_ATT_P 5
+ param set MC_YAWPOS_D 0.1
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 1
+ param set MC_YAWRATE_D 0
+ param set MC_YAWRATE_I 0
+ param set MC_YAWRATE_P 0.15
+
+ param set SYS_AUTOCONFIG 0
+ param save
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
+param set BAT_V_SCALING 0.008381
+
+#
+# Start MAVLink
+#
+mavlink start -d /dev/ttyS0 -b 57600
+usleep 5000
#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
-#
-# Start the sensors.
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start MAVLink
-#
-mavlink start -d /dev/ttyS0 -b 57600
-usleep 5000
-
-#
-# Start the commander.
-#
-commander start
-
-#
-# Start the attitude estimator
-#
-attitude_estimator_ekf start
-
-#
-# Fire up the multi rotor attitude controller
-#
-multirotor_att_control start
-
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
-
-#
-# Start logging
-#
-sdlog start -s 10
-
-#
-# Start GPS capture
-#
-gps start
-
-#
-# Start system state
-#
-if blinkm start
-then
- echo "using BlinkM for state indication"
- blinkm systemstate
-else
- echo "no BlinkM found, OK."
-fi
#
-# startup is done; we don't want the shell because we
-# use the same UART for telemetry
+# Start common for all multirotors apps
#
-echo "[init] startup done"
-
+sh /etc/init.d/rc.multirotor
+
+# Exit, because /dev/ttyS0 is needed for MAVLink
exit
diff --git a/ROMFS/px4fmu_common/init.d/09_ardrone_flow b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
index e7173f6e6e..9b739f2455 100644
--- a/ROMFS/px4fmu_common/init.d/09_ardrone_flow
+++ b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
@@ -1,55 +1,59 @@
#!nsh
-#
-# Flight startup script for PX4FMU on PX4IOAR carrier board.
-#
-# Disable the USB interface
-set USB no
+echo "[init] 09_ardrone_flow: PX4FMU on PX4IOAR carrier board with PX4FLOW"
-# Disable autostarting other apps
-set MODE ardrone
-
-echo "[init] doing PX4IOAR startup..."
-
#
-# Start the ORB
+# Load default params for this platform
#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
+if param compare SYS_AUTOCONFIG 1
then
- param load /fs/microsd/params
+ # Set all params here, then disable autoconfig
+ param set MC_ATTRATE_D 0
+ param set MC_ATTRATE_I 0
+ param set MC_ATTRATE_P 0.13
+ param set MC_ATT_D 0
+ param set MC_ATT_I 0.3
+ param set MC_ATT_P 5
+ param set MC_YAWPOS_D 0.1
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 1
+ param set MC_YAWRATE_D 0
+ param set MC_YAWRATE_I 0
+ param set MC_YAWRATE_P 0.15
+
+ param set SYS_AUTOCONFIG 0
+ param save
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
+param set BAT_V_SCALING 0.008381
+
+#
+# Start MAVLink and MAVLink Onboard (PX4FLOW Sensor)
+#
+mavlink start -d /dev/ttyS0 -b 57600
+mavlink_onboard start -d /dev/ttyS3 -b 115200
+usleep 5000
#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
+
+#
+# Fire up the AR.Drone interface.
+#
+ardrone_interface start -d /dev/ttyS1
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
-#
-# Start MAVLink and MAVLink Onboard (Flow Sensor)
-#
-mavlink start -d /dev/ttyS0 -b 57600
-mavlink_onboard start -d /dev/ttyS3 -b 115200
-usleep 5000
-
#
# Start the commander.
#
@@ -79,16 +83,6 @@ flow_position_control start
# Fire up the flow speed controller
#
flow_speed_control start
-
-#
-# Fire up the AR.Drone interface.
-#
-ardrone_interface start -d /dev/ttyS1
-#
-# startup is done; we don't want the shell because we
-# use the same UART for telemetry
-#
-echo "[init] startup done"
-
+# Exit, because /dev/ttyS0 is needed for MAVLink
exit
diff --git a/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
new file mode 100644
index 0000000000..40a13b5d17
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
@@ -0,0 +1,87 @@
+#!nsh
+#
+# USB HIL start
+#
+
+echo "[HIL] HILStar starting.."
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+
+ param set FW_P_D 0
+ param set FW_P_I 0
+ param set FW_P_IMAX 15
+ param set FW_P_LIM_MAX 50
+ param set FW_P_LIM_MIN -50
+ param set FW_P_P 60
+ param set FW_P_RMAX_NEG 0
+ param set FW_P_RMAX_POS 0
+ param set FW_P_ROLLFF 1.1
+ param set FW_R_D 0
+ param set FW_R_I 5
+ param set FW_R_IMAX 20
+ param set FW_R_P 100
+ param set FW_R_RMAX 100
+ param set FW_THR_CRUISE 0.65
+ param set FW_THR_MAX 1
+ param set FW_THR_MIN 0
+ param set FW_T_SINK_MAX 5.0
+ param set FW_T_SINK_MIN 4.0
+ param set FW_Y_ROLLFF 1.1
+ param set FW_L1_PERIOD 16
+ param set RC_SCALE_ROLL 1.0
+ param set RC_SCALE_PITCH 1.0
+
+ param set SYS_AUTOCONFIG 0
+ param save
+fi
+
+# Allow USB some time to come up
+sleep 1
+# Tell MAVLink that this link is "fast"
+mavlink start -b 230400 -d /dev/ttyACM0
+
+# Create a fake HIL /dev/pwm_output interface
+hil mode_pwm
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
+# see https://pixhawk.ethz.ch/mavlink/
+#
+param set MAV_TYPE 1
+
+#
+# Check if we got an IO
+#
+if px4io start
+then
+ echo "IO started"
+else
+ fmu mode_serial
+ echo "FMU started"
+fi
+
+#
+# Start the sensors (depends on orb, px4io)
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start the attitude estimator (depends on orb)
+#
+att_pos_estimator_ekf start
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
+fw_pos_control_l1 start
+fw_att_control start
+
+echo "[HIL] setup done, running"
+
diff --git a/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil b/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
new file mode 100644
index 0000000000..9b664d63ed
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
@@ -0,0 +1,105 @@
+#!nsh
+#
+# USB HIL start
+#
+
+echo "[HIL] HILS quadrotor starting.."
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.0
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.05
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 3.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.1
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.05
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.5
+ param set MPC_THR_MIN 0.1
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ param save
+fi
+
+# Allow USB some time to come up
+sleep 1
+# Tell MAVLink that this link is "fast"
+mavlink start -b 230400 -d /dev/ttyACM0
+
+# Create a fake HIL /dev/pwm_output interface
+hil mode_pwm
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
+# see https://pixhawk.ethz.ch/mavlink/
+#
+param set MAV_TYPE 2
+
+#
+# Check if we got an IO
+#
+if px4io start
+then
+ echo "IO started"
+else
+ fmu mode_serial
+ echo "FMU started"
+fi
+
+#
+# Start the sensors (depends on orb, px4io)
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start the attitude estimator (depends on orb)
+#
+att_pos_estimator_ekf start
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+
+#
+# Start position estimator
+#
+position_estimator_inav start
+
+#
+# Start attitude control
+#
+multirotor_att_control start
+
+#
+# Start position control
+#
+multirotor_pos_control start
+
+echo "[HIL] setup done, running"
+
diff --git a/ROMFS/px4fmu_common/init.d/1002_rc_fw_state.hil b/ROMFS/px4fmu_common/init.d/1002_rc_fw_state.hil
new file mode 100644
index 0000000000..7b9f41bf6d
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/1002_rc_fw_state.hil
@@ -0,0 +1,79 @@
+#!nsh
+#
+# USB HIL start
+#
+
+echo "[HIL] HILStar starting in state-HIL mode.."
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+
+ param set FW_P_D 0
+ param set FW_P_I 0
+ param set FW_P_IMAX 15
+ param set FW_P_LIM_MAX 50
+ param set FW_P_LIM_MIN -50
+ param set FW_P_P 60
+ param set FW_P_RMAX_NEG 0
+ param set FW_P_RMAX_POS 0
+ param set FW_P_ROLLFF 1.1
+ param set FW_R_D 0
+ param set FW_R_I 5
+ param set FW_R_IMAX 20
+ param set FW_R_P 100
+ param set FW_R_RMAX 100
+ param set FW_THR_CRUISE 0.65
+ param set FW_THR_MAX 1
+ param set FW_THR_MIN 0
+ param set FW_T_SINK_MAX 5.0
+ param set FW_T_SINK_MIN 4.0
+ param set FW_Y_ROLLFF 1.1
+
+ param set SYS_AUTOCONFIG 0
+ param save
+fi
+
+# Allow USB some time to come up
+sleep 1
+# Tell MAVLink that this link is "fast"
+mavlink start -b 230400 -d /dev/ttyACM0
+
+# Create a fake HIL /dev/pwm_output interface
+hil mode_pwm
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
+# see https://pixhawk.ethz.ch/mavlink/
+#
+param set MAV_TYPE 1
+
+#
+# Check if we got an IO
+#
+if px4io start
+then
+ echo "IO started"
+else
+ fmu mode_serial
+ echo "FMU started"
+fi
+
+#
+# Start the sensors (depends on orb, px4io)
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
+fw_pos_control_l1 start
+fw_att_control start
+
+echo "[HIL] setup done, running"
+
diff --git a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
new file mode 100644
index 0000000000..0cc07ad343
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
@@ -0,0 +1,105 @@
+#!nsh
+#
+# USB HIL start
+#
+
+echo "[HIL] HILS quadrotor + starting.."
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.0
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.05
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 3.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.1
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.05
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.5
+ param set MPC_THR_MIN 0.1
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ param save
+fi
+
+# Allow USB some time to come up
+sleep 1
+# Tell MAVLink that this link is "fast"
+mavlink start -b 230400 -d /dev/ttyACM0
+
+# Create a fake HIL /dev/pwm_output interface
+hil mode_pwm
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
+# see https://pixhawk.ethz.ch/mavlink/
+#
+param set MAV_TYPE 2
+
+#
+# Check if we got an IO
+#
+if px4io start
+then
+ echo "IO started"
+else
+ fmu mode_serial
+ echo "FMU started"
+fi
+
+#
+# Start the sensors (depends on orb, px4io)
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start the attitude estimator (depends on orb)
+#
+att_pos_estimator_ekf start
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
+
+#
+# Start position estimator
+#
+position_estimator_inav start
+
+#
+# Start attitude control
+#
+multirotor_att_control start
+
+#
+# Start position control
+#
+multirotor_pos_control start
+
+echo "[HIL] setup done, running"
+
diff --git a/ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil b/ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil
new file mode 100644
index 0000000000..344d784224
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil
@@ -0,0 +1,98 @@
+#!nsh
+#
+# USB HIL start
+#
+
+echo "[HIL] HILStar starting.."
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+
+ param set FW_P_D 0
+ param set FW_P_I 0
+ param set FW_P_IMAX 15
+ param set FW_P_LIM_MAX 50
+ param set FW_P_LIM_MIN -50
+ param set FW_P_P 60
+ param set FW_P_RMAX_NEG 0
+ param set FW_P_RMAX_POS 0
+ param set FW_P_ROLLFF 1.1
+ param set FW_R_D 0
+ param set FW_R_I 5
+ param set FW_R_IMAX 20
+ param set FW_R_P 100
+ param set FW_R_RMAX 100
+ param set FW_THR_CRUISE 0.65
+ param set FW_THR_MAX 1
+ param set FW_THR_MIN 0
+ param set FW_T_SINK_MAX 5.0
+ param set FW_T_SINK_MIN 4.0
+ param set FW_Y_ROLLFF 1.1
+ param set FW_L1_PERIOD 16
+ param set RC_SCALE_ROLL 1.0
+ param set RC_SCALE_PITCH 1.0
+
+ param set SYS_AUTOCONFIG 0
+ param save
+fi
+
+# Allow USB some time to come up
+sleep 1
+# Tell MAVLink that this link is "fast"
+mavlink start -b 230400 -d /dev/ttyACM0
+
+# Create a fake HIL /dev/pwm_output interface
+hil mode_pwm
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
+# see https://pixhawk.ethz.ch/mavlink/
+#
+param set MAV_TYPE 1
+
+#
+# Check if we got an IO
+#
+if px4io start
+then
+ echo "IO started"
+else
+ fmu mode_serial
+ echo "FMU started"
+fi
+
+#
+# Start the sensors (depends on orb, px4io)
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start the attitude estimator (depends on orb)
+#
+att_pos_estimator_ekf start
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+set MODE autostart
+mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
+if [ -f /fs/microsd/etc/mixers/FMU_AERT.mix ]
+then
+ echo "Using /fs/microsd/etc/mixers/FMU_AERT.mix"
+ mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_AERT.mix
+else
+ echo "Using /etc/mixers/FMU_AERT.mix"
+ mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
+fi
+
+
+fw_pos_control_l1 start
+fw_att_control start
+
+echo "[HIL] setup done, running"
+
diff --git a/ROMFS/px4fmu_common/init.d/100_mpx_easystar b/ROMFS/px4fmu_common/init.d/100_mpx_easystar
new file mode 100644
index 0000000000..abe378b22f
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/100_mpx_easystar
@@ -0,0 +1,87 @@
+#!nsh
+
+echo "[init] PX4FMU v1, v2 with or without IO on EasyStar"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set FW_P_D 0
+ param set FW_P_I 0
+ param set FW_P_IMAX 15
+ param set FW_P_LIM_MAX 50
+ param set FW_P_LIM_MIN -50
+ param set FW_P_P 60
+ param set FW_P_RMAX_NEG 0
+ param set FW_P_RMAX_POS 0
+ param set FW_P_ROLLFF 1.1
+ param set FW_R_D 0
+ param set FW_R_I 5
+ param set FW_R_IMAX 20
+ param set FW_R_P 100
+ param set FW_R_RMAX 100
+ param set FW_THR_CRUISE 0.65
+ param set FW_THR_MAX 1
+ param set FW_THR_MIN 0
+ param set FW_T_SINK_MAX 5.0
+ param set FW_T_SINK_MIN 4.0
+ param set FW_Y_ROLLFF 1.1
+ param set FW_L1_PERIOD 16
+ param set RC_SCALE_ROLL 1.0
+ param set RC_SCALE_PITCH 1.0
+
+ param set SYS_AUTOCONFIG 0
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing
+#
+param set MAV_TYPE 1
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+
+ sh /etc/init.d/rc.io
+ # Limit to 100 Hz updates and (implicit) 50 Hz PWM
+ px4io limit 100
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+if [ -f /fs/microsd/etc/mixers/FMU_RET.mix ]
+then
+ echo "Using /fs/microsd/etc/mixers/FMU_RET.mix"
+ mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_RET.mix
+else
+ echo "Using /etc/mixers/FMU_RET.mix"
+ mixer load /dev/pwm_output /etc/mixers/FMU_RET.mix
+fi
+
+#
+# Start common fixedwing apps
+#
+sh /etc/init.d/rc.fixedwing
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/101_hk_bixler b/ROMFS/px4fmu_common/init.d/101_hk_bixler
new file mode 100644
index 0000000000..c616da9886
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/101_hk_bixler
@@ -0,0 +1,87 @@
+#!nsh
+
+echo "[init] PX4FMU v1, v2 with or without IO on HK Bixler"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set FW_P_D 0
+ param set FW_P_I 0
+ param set FW_P_IMAX 15
+ param set FW_P_LIM_MAX 50
+ param set FW_P_LIM_MIN -50
+ param set FW_P_P 60
+ param set FW_P_RMAX_NEG 0
+ param set FW_P_RMAX_POS 0
+ param set FW_P_ROLLFF 1.1
+ param set FW_R_D 0
+ param set FW_R_I 5
+ param set FW_R_IMAX 20
+ param set FW_R_P 100
+ param set FW_R_RMAX 100
+ param set FW_THR_CRUISE 0.65
+ param set FW_THR_MAX 1
+ param set FW_THR_MIN 0
+ param set FW_T_SINK_MAX 5.0
+ param set FW_T_SINK_MIN 4.0
+ param set FW_Y_ROLLFF 1.1
+ param set FW_L1_PERIOD 16
+ param set RC_SCALE_ROLL 1.0
+ param set RC_SCALE_PITCH 1.0
+
+ param set SYS_AUTOCONFIG 0
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing
+#
+param set MAV_TYPE 1
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+
+ sh /etc/init.d/rc.io
+ # Limit to 100 Hz updates and (implicit) 50 Hz PWM
+ px4io limit 100
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+if [ -f /fs/microsd/etc/mixers/FMU_AERT.mix ]
+then
+ echo "Using /fs/microsd/etc/mixers/FMU_AERT.mix"
+ mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_AERT.mix
+else
+ echo "Using /etc/mixers/FMU_Q.mix"
+ mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
+fi
+
+#
+# Start common fixedwing apps
+#
+sh /etc/init.d/rc.fixedwing
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/10_dji_f330 b/ROMFS/px4fmu_common/init.d/10_dji_f330
new file mode 100644
index 0000000000..467b56bbf9
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/10_dji_f330
@@ -0,0 +1,97 @@
+#!nsh
+
+echo "[init] PX4FMU v1, v2 with or without IO on DJI F330"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.004
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 7.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.7
+ param set MPC_THR_MIN 0.3
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
+
+ sh /etc/init.d/rc.io
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+
+#
+# Set PWM output frequency
+#
+pwm rate -c 1234 -r 400
+
+#
+# Set disarmed, min and max PWM signals (for DJI ESCs)
+#
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1200
+pwm max -c 1234 -p 1800
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/10_io_f330 b/ROMFS/px4fmu_common/init.d/10_io_f330
deleted file mode 100644
index 4450eb50db..0000000000
--- a/ROMFS/px4fmu_common/init.d/10_io_f330
+++ /dev/null
@@ -1,116 +0,0 @@
-#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
-
- param set MC_ATTRATE_D 0.005
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.1
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 4.5
- param set MC_RCLOSS_THR 0.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.3
- param set MC_YAWPOS_P 0.6
- param set MC_YAWRATE_D 0.0
- param set MC_YAWRATE_I 0.0
- param set MC_YAWRATE_P 0.1
-
- param save /fs/microsd/params
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
-#
-param set MAV_TYPE 2
-
-#
-# Start MAVLink (depends on orb)
-#
-mavlink start
-usleep 5000
-
-#
-# Start PX4IO interface (depends on orb, commander)
-#
-px4io start
-pwm -u 400 -m 0xff
-
-#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
-
-#
-# Disable px4io topic limiting
-#
-px4io limit 200
-
-#
-# This sets a PWM right after startup (regardless of safety button)
-#
-px4io idle 900 900 900 900
-
-#
-# The values are for spinning motors when armed using DJI ESCs
-#
-px4io min 1200 1200 1200 1200
-
-#
-# Upper limits could be higher, this is on the safe side
-#
-px4io max 1800 1800 1800 1800
-
-#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start the commander (depends on orb, mavlink)
-#
-commander start
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator (depends on orb)
-#
-attitude_estimator_ekf start
-
-#
-# Load mixer and start controllers (depends on px4io)
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-multirotor_att_control start
-
-#
-# Start logging
-#
-sdlog2 start -r 20 -a -b 16
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
diff --git a/ROMFS/px4fmu_common/init.d/11_dji_f450 b/ROMFS/px4fmu_common/init.d/11_dji_f450
new file mode 100644
index 0000000000..818f9375e4
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/11_dji_f450
@@ -0,0 +1,83 @@
+#!nsh
+
+echo "[init] PX4FMU v1, v2 with or without IO on DJI F450"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.004
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 7.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
+
+ commander start
+
+ sh /etc/init.d/rc.io
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+
+#
+# Set PWM output frequency
+#
+pwm rate -c 1234 -r 400
+
+#
+# Set disarmed, min and max PWM signals (for DJI ESCs)
+#
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1200
+pwm max -c 1234 -p 1800
+
+#
+# Start common multirotor apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/12-13_hex b/ROMFS/px4fmu_common/init.d/12-13_hex
new file mode 100644
index 0000000000..f83f6cfd05
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/12-13_hex
@@ -0,0 +1,98 @@
+#!nsh
+
+echo "[init] PX4FMU v1, v2 with or without IO on Hex"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.004
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 7.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.7
+ param set MPC_THR_MIN 0.3
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE list: https://pixhawk.ethz.ch/mavlink/
+# 13 = hexarotor
+#
+param set MAV_TYPE 13
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
+
+ sh /etc/init.d/rc.io
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_hex_x.mix
+
+#
+# Set PWM output frequency to 400 Hz
+#
+pwm rate -c 123456 -r 400
+
+#
+# Set disarmed, min and max PWM signals
+#
+pwm disarmed -c 123456 -p 900
+pwm min -c 123456 -p 1100
+pwm max -c 123456 -p 1900
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/15_tbs_discovery b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
new file mode 100644
index 0000000000..c79e9d2830
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
@@ -0,0 +1,81 @@
+#!nsh
+
+echo "[init] Team Blacksheep Discovery Quad"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.006
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.17
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 5.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 0.5
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.2
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
+
+ sh /etc/init.d/rc.io
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load the mixer for a quad with wide arms
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
+
+#
+# Set PWM output frequency
+#
+pwm rate -c 1234 -r 400
+
+#
+# Set disarmed, min and max PWM signals
+#
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1100
+pwm max -c 1234 -p 1900
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/16_3dr_iris b/ROMFS/px4fmu_common/init.d/16_3dr_iris
new file mode 100644
index 0000000000..6be9178786
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/16_3dr_iris
@@ -0,0 +1,81 @@
+#!nsh
+
+echo "[init] 3DR Iris Quad"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.004
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.13
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 9.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 0.5
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.2
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
+
+ sh /etc/init.d/rc.io
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.0098
+ set EXIT_ON_END yes
+fi
+
+#
+# Load the mixer for a quad with wide arms
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
+
+#
+# Set PWM output frequency
+#
+pwm rate -c 1234 -r 400
+
+#
+# Set disarmed, min and max PWM signals
+#
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1200
+pwm max -c 1234 -p 1800
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/30_io_camflyer b/ROMFS/px4fmu_common/init.d/30_io_camflyer
index 5090b98a42..8a8bc15903 100644
--- a/ROMFS/px4fmu_common/init.d/30_io_camflyer
+++ b/ROMFS/px4fmu_common/init.d/30_io_camflyer
@@ -1,26 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+
+echo "[init] PX4FMU v1, v2 with or without IO on Camflyer"
#
# Load default params for this platform
@@ -28,94 +8,58 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
+ # TODO
+
param set SYS_AUTOCONFIG 0
- param save /fs/microsd/params
+ param save
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 1 = fixed wing
#
param set MAV_TYPE 1
-
-#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- then
- echo "No newer version, skipping upgrade."
- else
- echo "Loading /fs/microsd/px4io.bin"
- if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
- then
- cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
- else
- echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
- echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
- fi
- fi
-fi
-
-#
-# Start MAVLink (depends on orb)
-#
-mavlink start -d /dev/ttyS1 -b 57600
-usleep 5000
-
-#
-# Start the commander (depends on orb, mavlink)
-#
-commander start
-
-#
-# Start PX4IO interface (depends on orb, commander)
-#
-px4io start
-
-#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
+
+set EXIT_ON_END no
#
-# Set actuator limit to 100 Hz update (50 Hz PWM)
-px4io limit 100
-
+# Start and configure PX4IO or FMU interface
#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator (depends on orb)
-#
-kalman_demo start
-
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+
+ sh /etc/init.d/rc.io
+ # Limit to 100 Hz updates and (implicit) 50 Hz PWM
+ px4io limit 100
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
#
# Load mixer and start controllers (depends on px4io)
#
-mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
-control_demo start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
+if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
then
- blinkm systemstate
+ echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
+ mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
+else
+ echo "Using /etc/mixers/FMU_Q.mix"
+ mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
fi
+
+#
+# Start common fixedwing apps
+#
+sh /etc/init.d/rc.fixedwing
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
\ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/31_io_phantom b/ROMFS/px4fmu_common/init.d/31_io_phantom
index 5090b98a42..63cd7f9b2e 100644
--- a/ROMFS/px4fmu_common/init.d/31_io_phantom
+++ b/ROMFS/px4fmu_common/init.d/31_io_phantom
@@ -1,26 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+
+echo "[init] PX4FMU v1, v2 with or without IO on Phantom FPV"
#
# Load default params for this platform
@@ -28,94 +8,80 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
+ param set FW_P_D 0
+ param set FW_P_I 0
+ param set FW_P_IMAX 15
+ param set FW_P_LIM_MAX 50
+ param set FW_P_LIM_MIN -50
+ param set FW_P_P 60
+ param set FW_P_RMAX_NEG 0
+ param set FW_P_RMAX_POS 0
+ param set FW_P_ROLLFF 1.1
+ param set FW_R_D 0
+ param set FW_R_I 5
+ param set FW_R_IMAX 20
+ param set FW_R_P 100
+ param set FW_R_RMAX 100
+ param set FW_THR_CRUISE 0.65
+ param set FW_THR_MAX 1
+ param set FW_THR_MIN 0
+ param set FW_T_SINK_MAX 5.0
+ param set FW_T_SINK_MIN 4.0
+ param set FW_Y_ROLLFF 1.1
+ param set FW_L1_PERIOD 17
+ param set RC_SCALE_ROLL 1.0
+ param set RC_SCALE_PITCH 1.0
+
param set SYS_AUTOCONFIG 0
- param save /fs/microsd/params
+ param save
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 1 = fixed wing
#
param set MAV_TYPE 1
-
-#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- then
- echo "No newer version, skipping upgrade."
- else
- echo "Loading /fs/microsd/px4io.bin"
- if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
- then
- cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
- else
- echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
- echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
- fi
- fi
-fi
-
-#
-# Start MAVLink (depends on orb)
-#
-mavlink start -d /dev/ttyS1 -b 57600
-usleep 5000
-
-#
-# Start the commander (depends on orb, mavlink)
-#
-commander start
-
-#
-# Start PX4IO interface (depends on orb, commander)
-#
-px4io start
-
-#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
+
+set EXIT_ON_END no
#
-# Set actuator limit to 100 Hz update (50 Hz PWM)
-px4io limit 100
-
+# Start and configure PX4IO or FMU interface
#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator (depends on orb)
-#
-kalman_demo start
-
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+
+ sh /etc/init.d/rc.io
+ # Limit to 100 Hz updates and (implicit) 50 Hz PWM
+ px4io limit 100
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
#
# Load mixer and start controllers (depends on px4io)
#
-mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
-control_demo start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
+if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
then
- blinkm systemstate
+ echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
+ mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
+else
+ echo "Using /etc/mixers/FMU_Q.mix"
+ mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
fi
+
+#
+# Start common fixedwing apps
+#
+sh /etc/init.d/rc.fixedwing
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
\ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/32_skywalker_x5 b/ROMFS/px4fmu_common/init.d/32_skywalker_x5
new file mode 100644
index 0000000000..1e752f13a2
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/32_skywalker_x5
@@ -0,0 +1,65 @@
+#!nsh
+
+echo "[init] PX4FMU v1, v2 with or without IO on Skywalker X5"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ # TODO
+
+ param set SYS_AUTOCONFIG 0
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing
+#
+param set MAV_TYPE 1
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+
+ sh /etc/init.d/rc.io
+ # Limit to 100 Hz updates and (implicit) 50 Hz PWM
+ px4io limit 100
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
+then
+ echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
+ mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
+else
+ echo "Using /etc/mixers/FMU_Q.mix"
+ mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
+fi
+
+#
+# Start common fixedwing apps
+#
+sh /etc/init.d/rc.fixedwing
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/40_io_segway b/ROMFS/px4fmu_common/init.d/40_io_segway
index 5742d685aa..fb9dec0437 100644
--- a/ROMFS/px4fmu_common/init.d/40_io_segway
+++ b/ROMFS/px4fmu_common/init.d/40_io_segway
@@ -1,26 +1,4 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
#
# Load default params for this platform
@@ -28,65 +6,34 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
+ # TODO
+
param set SYS_AUTOCONFIG 0
- param save /fs/microsd/params
+ param save
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 10 = ground rover
#
param set MAV_TYPE 10
-
-#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- then
- echo "No newer version, skipping upgrade."
- else
- echo "Loading /fs/microsd/px4io.bin"
- if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
- then
- cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
- else
- echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
- echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
- fi
- fi
-fi
-
+
#
# Start MAVLink (depends on orb)
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
+#
+# Start and configure PX4IO interface
+#
+sh /etc/init.d/rc.io
+
#
# Start the commander (depends on orb, mavlink)
#
commander start
-
-#
-# Start PX4IO interface (depends on orb, commander)
-#
-px4io start
-
-#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
-#
-# Disable px4io topic limiting
-#
-px4io limit 200
-
#
# Start the sensors (depends on orb, px4io)
#
@@ -105,18 +52,5 @@ attitude_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
#
-md25 start 3 0x58
+roboclaw start /dev/ttyS2 128 1200
segway start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
diff --git a/ROMFS/px4fmu_common/init.d/666_fmu_q_x550 b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
new file mode 100644
index 0000000000..1ee84b9b01
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
@@ -0,0 +1,83 @@
+#!nsh
+
+echo "[init] 666_fmu_q_x550: PX4FMU Quad X550 with or without IO"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set MC_ATTRATE_P 0.14
+ param set MC_ATTRATE_I 0
+ param set MC_ATTRATE_D 0.006
+ param set MC_ATT_P 5.5
+ param set MC_ATT_I 0
+ param set MC_ATT_D 0
+ param set MC_YAWPOS_D 0
+ param set MC_YAWPOS_I 0
+ param set MC_YAWPOS_P 0.6
+ param set MC_YAWRATE_D 0
+ param set MC_YAWRATE_I 0
+ param set MC_YAWRATE_P 0.08
+ param set RC_SCALE_PITCH 1
+ param set RC_SCALE_ROLL 1
+ param set RC_SCALE_YAW 3
+
+ param set SYS_AUTOCONFIG 0
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
+
+ sh /etc/init.d/rc.io
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+
+#
+# Set PWM output frequency
+#
+pwm rate -c 1234 -r 400
+
+#
+# Set disarmed, min and max PWM signals
+#
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1100
+pwm max -c 1234 -p 1900
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/cmp_test b/ROMFS/px4fmu_common/init.d/cmp_test
new file mode 100644
index 0000000000..f86f4f85bb
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/cmp_test
@@ -0,0 +1,9 @@
+#!nsh
+
+cp /etc/extras/px4io-v2_default.bin /fs/microsd/px4io.loaded
+if cmp /etc/extras/px4io-v2_default.bin /fs/microsd/px4io.loaded
+then
+ echo "CMP returned true"
+else
+ echo "CMP returned false"
+fi
\ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/rc.boarddetect b/ROMFS/px4fmu_common/init.d/rc.boarddetect
deleted file mode 100644
index f233e51df4..0000000000
--- a/ROMFS/px4fmu_common/init.d/rc.boarddetect
+++ /dev/null
@@ -1,66 +0,0 @@
-#!nsh
-#
-# If we are still in flight mode, work out what airframe
-# configuration we have and start up accordingly.
-#
-if [ $MODE != autostart ]
-then
- echo "[init] automatic startup cancelled by user script"
-else
- echo "[init] detecting attached hardware..."
-
- #
- # Assume that we are PX4FMU in standalone mode
- #
- set BOARD PX4FMU
-
- #
- # Are we attached to a PX4IOAR (AR.Drone carrier board)?
- #
- if boardinfo test name PX4IOAR
- then
- set BOARD PX4IOAR
- if [ -f /etc/init.d/rc.PX4IOAR ]
- then
- echo "[init] reading /etc/init.d/rc.PX4IOAR"
- usleep 500
- sh /etc/init.d/rc.PX4IOAR
- fi
- else
- echo "[init] PX4IOAR not detected"
- fi
-
- #
- # Are we attached to a PX4IO?
- #
- if boardinfo test name PX4IO
- then
- set BOARD PX4IO
- if [ -f /etc/init.d/rc.PX4IO ]
- then
- echo "[init] reading /etc/init.d/rc.PX4IO"
- usleep 500
- sh /etc/init.d/rc.PX4IO
- fi
- else
- echo "[init] PX4IO not detected"
- fi
-
- #
- # Looks like we are stand-alone
- #
- if [ $BOARD == PX4FMU ]
- then
- echo "[init] no expansion board detected"
- if [ -f /etc/init.d/rc.standalone ]
- then
- echo "[init] reading /etc/init.d/rc.standalone"
- sh /etc/init.d/rc.standalone
- fi
- fi
-
- #
- # We may not reach here if the airframe-specific script exits the shell.
- #
- echo "[init] startup done."
-fi
\ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl b/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
new file mode 100644
index 0000000000..4686382ca6
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
@@ -0,0 +1,120 @@
+#!nsh
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.002
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.09
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 6.8
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.7
+ param set MPC_THR_MIN 0.3
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+set EXIT_ON_END no
+
+#
+# Start the Mikrokopter ESC driver
+#
+if [ $MKBLCTRL_MODE == yes ]
+then
+ if [ $MKBLCTRL_FRAME == x ]
+ then
+ echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing"
+ mkblctrl -mkmode x
+ else
+ echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing"
+ mkblctrl -mkmode +
+ fi
+else
+ if [ $MKBLCTRL_FRAME == x ]
+ then
+ echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame"
+ else
+ echo "[init] PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame"
+ fi
+ mkblctrl
+fi
+
+usleep 10000
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
+
+ sh /etc/init.d/rc.io
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer
+#
+if [ $MKBLCTRL_FRAME == x ]
+then
+ mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+else
+ mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
+fi
+
+#
+# Set disarmed, min and max PWM signals
+#
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1200
+pwm max -c 1234 -p 1800
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.custom_io_esc b/ROMFS/px4fmu_common/init.d/rc.custom_io_esc
new file mode 100644
index 0000000000..045e41e529
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.custom_io_esc
@@ -0,0 +1,120 @@
+#!nsh
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.002
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.09
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 6.8
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.7
+ param set MPC_THR_MIN 0.3
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 3
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.1
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ param save
+fi
+
+echo "RC script for PX4FMU + PX4IO + PPM-ESCs running"
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+set EXIT_ON_END no
+
+usleep 10000
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start -d /dev/ttyS1 -b 57600
+ usleep 5000
+
+ sh /etc/init.d/rc.io
+else
+ fmu mode_pwm
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS1 -b 57600
+ usleep 5000
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+if [ $ESC_MAKER = afro ]
+then
+ # Set PWM values for Afro ESCs
+ pwm disarmed -c 1234 -p 1050
+ pwm min -c 1234 -p 1080
+ pwm max -c 1234 -p 1860
+else
+ # Set PWM values for typical ESCs
+ pwm disarmed -c 1234 -p 900
+ pwm min -c 1234 -p 980
+ pwm max -c 1234 -p 1800
+fi
+
+#
+# Load mixer
+#
+if [ $FRAME_GEOMETRY == x ]
+then
+ echo "Frame geometry X"
+ mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+else
+ if [ $FRAME_GEOMETRY == w ]
+ then
+ echo "Frame geometry W"
+ mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
+ else
+ echo "Frame geometry +"
+ mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
+ fi
+fi
+
+#
+# Set PWM output frequency
+#
+pwm rate -r 400 -c 1234
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
+
+echo "Script end"
diff --git a/ROMFS/px4fmu_common/init.d/rc.fixedwing b/ROMFS/px4fmu_common/init.d/rc.fixedwing
new file mode 100644
index 0000000000..f028510064
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.fixedwing
@@ -0,0 +1,34 @@
+#!nsh
+#
+# Standard everything needed for fixedwing except mixer, actuator output and mavlink
+#
+
+#
+# Start the sensors and test them.
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start logging (depends on sensors)
+#
+sh /etc/init.d/rc.logging
+
+#
+# Start GPS interface (depends on orb)
+#
+gps start
+
+#
+# Start the attitude and position estimator
+#
+att_pos_estimator_ekf start
+
+#
+# Start attitude controller
+#
+fw_att_control start
+
+#
+# Start the position controller
+#
+fw_pos_control_l1 start
diff --git a/ROMFS/px4fmu_common/init.d/rc.hil b/ROMFS/px4fmu_common/init.d/rc.hil
deleted file mode 100644
index 3517a5bd82..0000000000
--- a/ROMFS/px4fmu_common/init.d/rc.hil
+++ /dev/null
@@ -1,68 +0,0 @@
-#!nsh
-#
-# USB HIL start
-#
-
-echo "[HIL] starting.."
-
-uorb start
-
-# Tell MAVLink that this link is "fast"
-mavlink start -b 230400 -d /dev/console
-
-# Create a fake HIL /dev/pwm_output interface
-hil mode_pwm
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
-#
-param set MAV_TYPE 1
-
-#
-# Start the commander (depends on orb, mavlink)
-#
-commander start
-
-#
-# Check if we got an IO
-#
-if [ px4io start ]
-then
- echo "IO started"
-else
- fmu mode_serial
- echo "FMU started"
-end
-
-#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start the attitude estimator (depends on orb)
-#
-att_pos_estimator_ekf start
-
-#
-# Load mixer and start controllers (depends on px4io)
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
-fixedwing_backside start
-
-echo "[HIL] setup done, running"
-
-# Exit shell to make it available to MAVLink
-exit
diff --git a/ROMFS/px4fmu_common/init.d/rc.io b/ROMFS/px4fmu_common/init.d/rc.io
new file mode 100644
index 0000000000..aaf91b3166
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.io
@@ -0,0 +1,23 @@
+#
+# Start PX4IO interface (depends on orb, commander)
+#
+if px4io start
+then
+ #
+ # Allow PX4IO to recover from midair restarts.
+ # this is very unlikely, but quite safe and robust.
+ px4io recovery
+
+ #
+ # Disable px4io topic limiting
+ #
+ if [ $BOARD == fmuv1 ]
+ then
+ px4io limit 200
+ else
+ px4io limit 400
+ fi
+else
+ # SOS
+ tone_alarm error
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index 09c2d00d19..dc4be8055a 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -5,5 +5,10 @@
if [ -d /fs/microsd ]
then
- sdlog start
+ if [ $BOARD == fmuv1 ]
+ then
+ sdlog2 start -r 50 -a -b 16
+ else
+ sdlog2 start -r 200 -a -b 16
+ fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.multirotor b/ROMFS/px4fmu_common/init.d/rc.multirotor
new file mode 100644
index 0000000000..bc550ac5a1
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.multirotor
@@ -0,0 +1,39 @@
+#!nsh
+#
+# Standard everything needed for multirotors except mixer, actuator output and mavlink
+#
+
+#
+# Start the sensors and test them.
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start logging (depends on sensors)
+#
+sh /etc/init.d/rc.logging
+
+#
+# Start GPS interface (depends on orb)
+#
+gps start
+
+#
+# Start the attitude estimator
+#
+attitude_estimator_ekf start
+
+#
+# Start position estimator
+#
+position_estimator_inav start
+
+#
+# Start attitude control
+#
+multirotor_att_control start
+
+#
+# Start position control
+#
+multirotor_pos_control start
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index 5e80ddc2f4..f17b650bc2 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -7,25 +7,40 @@
# Start sensor drivers here.
#
-#
-# Check for UORB
-#
-if uorb start
-then
- echo "uORB started"
-fi
-
ms5611 start
adc start
+# mag might be external
+if hmc5883 start
+then
+ echo "using HMC5883"
+fi
+
if mpu6000 start
then
- echo "using MPU6000 and HMC5883L"
- hmc5883 start
+ echo "using MPU6000"
+ set BOARD fmuv1
else
echo "using L3GD20 and LSM303D"
l3gd20 start
lsm303d start
+ set BOARD fmuv2
+fi
+
+# Start airspeed sensors
+if meas_airspeed start
+then
+ echo "using MEAS airspeed sensor"
+else
+ if ets_airspeed start
+ then
+ echo "using ETS airspeed sensor (bus 3)"
+ else
+ if ets_airspeed start -b 1
+ then
+ echo "Using ETS airspeed sensor (bus 1)"
+ fi
+ fi
fi
#
@@ -36,8 +51,5 @@ fi
#
if sensors start
then
- #
- # Check sensors - run AFTER 'sensors start'
- #
preflight_check &
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index 5b1bd272e9..ccf2cd47ea 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -8,14 +8,28 @@ 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
-sleep 2
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
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index f0ee1a0c6e..d8b5cb6087 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -20,7 +20,7 @@ then
else
echo "[init] no microSD card found"
# Play SOS
- tone_alarm 2
+ tone_alarm error
fi
#
@@ -57,90 +57,301 @@ fi
if [ $MODE == autostart ]
then
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-if ramtron start
-then
- param select /ramtron/params
- if [ -f /ramtron/params ]
+ #
+ # Start terminal
+ #
+ if sercon
then
- param load /ramtron/params
+ echo "USB connected"
fi
-else
- param select /fs/microsd/params
- if [ -f /fs/microsd/params ]
- then
- param load /fs/microsd/params
- fi
-fi
-
-#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.cur
- then
- echo "No newer version, skipping upgrade."
- else
- echo "Loading /fs/microsd/px4io.bin"
- if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io.log
+
+ #
+ # Start the ORB (first app to start)
+ #
+ uorb start
+
+ #
+ # Load microSD params
+ #
+ #if ramtron start
+ #then
+ # param select /ramtron/params
+ # if [ -f /ramtron/params ]
+ # then
+ # param load /ramtron/params
+ # fi
+ #else
+ param select /fs/microsd/params
+ if [ -f /fs/microsd/params ]
then
- cp /fs/microsd/px4io.bin /fs/microsd/px4io.cur
- echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io.log
- else
- echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io.log
- echo "Failed to upgrade px4io firmware - check if px4io is in bootloader mode"
+ if param load /fs/microsd/params
+ then
+ echo "Parameters loaded"
+ else
+ echo "Parameter file corrupt - ignoring"
+ fi
+ fi
+ #fi
+
+ #
+ # Start system state indicator
+ #
+ if rgbled start
+ then
+ echo "Using external RGB Led"
+ else
+ if blinkm start
+ then
+ blinkm systemstate
fi
fi
-fi
+
+ #
+ # Start the Commander (needs to be this early for in-air-restarts)
+ #
+ commander start
-#
-# Check if auto-setup from one of the standard scripts is wanted
-# SYS_AUTOSTART = 0 means no autostart (default)
-#
-if param compare SYS_AUTOSTART 1
-then
- sh /etc/init.d/01_fmu_quad_x
-fi
+ if param compare SYS_AUTOSTART 1000
+ then
+ sh /etc/init.d/1000_rc_fw_easystar.hil
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 1001
+ then
+ sh /etc/init.d/1001_rc_quad.hil
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 1002
+ then
+ sh /etc/init.d/1002_rc_fw_state.hil
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 1003
+ then
+ sh /etc/init.d/1003_rc_quad_+.hil
+ set MODE custom
+ fi
-if param compare SYS_AUTOSTART 2
-then
- sh /etc/init.d/02_io_quad_x
-fi
+ if param compare SYS_AUTOSTART 1004
+ then
+ sh /etc/init.d/1004_rc_fw_Rascal110.hil
+ set MODE custom
+ fi
+
+ if [ $MODE != custom ]
+ then
+ # Try to get an USB console
+ nshterm /dev/ttyACM0 &
+ fi
-if param compare SYS_AUTOSTART 8
-then
- sh /etc/init.d/08_ardrone
-fi
+
+ #
+ # Upgrade PX4IO firmware
+ #
+ if px4io detect
+ then
+ echo "PX4IO running, not upgrading"
+ else
+ echo "Attempting to upgrade PX4IO"
+ if px4io update
+ then
+ if [ -d /fs/microsd ]
+ then
+ echo "Flashed PX4IO Firmware OK" > /fs/microsd/px4io.log
+ fi
-if param compare SYS_AUTOSTART 9
-then
- sh /etc/init.d/09_ardrone_flow
-fi
+ # Allow IO to safely kick back to app
+ usleep 200000
+ else
+ echo "No PX4IO to upgrade here"
+ fi
+ fi
+
+ #
+ # Check if auto-setup from one of the standard scripts is wanted
+ # SYS_AUTOSTART = 0 means no autostart (default)
+ #
+
+ if param compare SYS_AUTOSTART 8
+ then
+ sh /etc/init.d/08_ardrone
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 9
+ then
+ sh /etc/init.d/09_ardrone_flow
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 10
+ then
+ sh /etc/init.d/10_dji_f330
+ set MODE custom
+ fi
-if param compare SYS_AUTOSTART 10
-then
- sh /etc/init.d/10_io_f330
-fi
+ if param compare SYS_AUTOSTART 11
+ then
+ sh /etc/init.d/11_dji_f450
+ set MODE custom
+ fi
-if param compare SYS_AUTOSTART 30
-then
- sh /etc/init.d/30_io_camflyer
-fi
+ if param compare SYS_AUTOSTART 12
+ then
+ set MIXER /etc/mixers/FMU_hex_x.mix
+ sh /etc/init.d/12-13_hex
+ set MODE custom
+ fi
-if param compare SYS_AUTOSTART 31
-then
- sh /etc/init.d/31_io_phantom
-fi
+ if param compare SYS_AUTOSTART 13
+ then
+ set MIXER /etc/mixers/FMU_hex_+.mix
+ sh /etc/init.d/12-13_hex
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 15
+ then
+ sh /etc/init.d/15_tbs_discovery
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 16
+ then
+ sh /etc/init.d/16_3dr_iris
+ set MODE custom
+ fi
+
+ # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame
+ if param compare SYS_AUTOSTART 17
+ then
+ set MKBLCTRL_MODE no
+ set MKBLCTRL_FRAME x
+ sh /etc/init.d/rc.custom_dji_f330_mkblctrl
+ set MODE custom
+ fi
+
+ # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame
+ if param compare SYS_AUTOSTART 18
+ then
+ set MKBLCTRL_MODE no
+ set MKBLCTRL_FRAME +
+ sh /etc/init.d/rc.custom_dji_f330_mkblctrl
+ set MODE custom
+ fi
+
+ # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 X Frame Mikrokopter-Addressing
+ if param compare SYS_AUTOSTART 19
+ then
+ set MKBLCTRL_MODE yes
+ set MKBLCTRL_FRAME x
+ sh /etc/init.d/rc.custom_dji_f330_mkblctrl
+ set MODE custom
+ fi
+
+ # PX4FMU v1, v2 with or without IO and Mikrokopter I2C ESCs on DJI F330 + Frame Mikrokopter-Addressing
+ if param compare SYS_AUTOSTART 20
+ then
+ set MKBLCTRL_MODE yes
+ set MKBLCTRL_FRAME +
+ sh /etc/init.d/rc.custom_dji_f330_mkblctrl
+ set MODE custom
+ fi
+
+ # PX4FMU v1 with IO + PPM-based ESCs on Quad X-shape frame
+ if param compare SYS_AUTOSTART 21
+ then
+ set FRAME_GEOMETRY x
+ set ESC_MAKER afro
+ sh /etc/init.d/rc.custom_io_esc
+ set MODE custom
+ fi
+
+ # PX4FMU v1 with IO + PPM-based ESCs on Quad X-shape frame
+ if param compare SYS_AUTOSTART 22
+ then
+ set FRAME_GEOMETRY w
+ sh /etc/init.d/rc.custom_io_esc
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 30
+ then
+ sh /etc/init.d/30_io_camflyer
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 31
+ then
+ sh /etc/init.d/31_io_phantom
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 32
+ then
+ sh /etc/init.d/32_skywalker_x5
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 40
+ then
+ sh /etc/init.d/40_io_segway
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 100
+ then
+ sh /etc/init.d/100_mpx_easystar
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 101
+ then
+ sh /etc/init.d/101_hk_bixler
+ set MODE custom
+ fi
+
+ # Start any custom extensions that might be missing
+ if [ -f /fs/microsd/etc/rc.local ]
+ then
+ sh /fs/microsd/etc/rc.local
+ fi
+
+ # If none of the autostart scripts triggered, get a minimal setup
+ if [ $MODE == autostart ]
+ then
+ # Telemetry port is on both FMU boards ttyS1
+ # but the AR.Drone motors can be get 'flashed'
+ # if starting MAVLink on them - so do not
+ # start it as default (default link: USB)
+
+ # Start commander
+ commander start
+
+ # Start px4io if present
+ if px4io detect
+ then
+ px4io start
+ else
+ if fmu mode_serial
+ then
+ echo "FMU driver (no PWM) started"
+ fi
+ fi
+
+ # Start sensors
+ sh /etc/init.d/rc.sensors
+
+ # Start one of the estimators
+ attitude_estimator_ekf start
+
+ # Start GPS
+ gps start
+
+ fi
# End of autostart
fi
diff --git a/ROMFS/px4fmu_common/mixers/FMU_AERT.mix b/ROMFS/px4fmu_common/mixers/FMU_AERT.mix
index 75e82bb00a..0ec663e35e 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_AERT.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_AERT.mix
@@ -62,3 +62,23 @@ range. Inputs below zero are treated as zero.
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
+
+
+Gimbal / flaps / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_AET.mix b/ROMFS/px4fmu_common/mixers/FMU_AET.mix
index 20cb88b916..c73cb2a62d 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_AET.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_AET.mix
@@ -58,3 +58,23 @@ range. Inputs below zero are treated as zero.
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
+
+
+Gimbal / flaps / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_Q.mix b/ROMFS/px4fmu_common/mixers/FMU_Q.mix
index ebcb66b248..17ff711513 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_Q.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_Q.mix
@@ -50,3 +50,21 @@ M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
+Gimbal / flaps / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_RET.mix b/ROMFS/px4fmu_common/mixers/FMU_RET.mix
index 95beb8927c..f07c34ac8a 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_RET.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_RET.mix
@@ -51,3 +51,23 @@ range. Inputs below zero are treated as zero.
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
+
+
+Gimbal / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_X5.mix b/ROMFS/px4fmu_common/mixers/FMU_X5.mix
index 9f81e1dc3a..6108683549 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_X5.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_X5.mix
@@ -48,3 +48,22 @@ M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
+Gimbal / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
+
diff --git a/ROMFS/px4fmu_common/mixers/FMU_delta.mix b/ROMFS/px4fmu_common/mixers/FMU_delta.mix
index 9814667041..f0aa6650d9 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_delta.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_delta.mix
@@ -48,3 +48,23 @@ M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
+
+Gimbal / flaps / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
+
diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix b/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix
index b5e38ce9ef..f8f9f0e4dc 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix
@@ -5,3 +5,14 @@ This file defines a single mixer for a hexacopter in the + configuration. All co
are mixed 100%.
R: 6+ 10000 10000 10000 0
+
+Gimbal / payload mixer for last two channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix b/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix
index 8e8d122adc..26b40b9e95 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix
@@ -5,3 +5,14 @@ This file defines a single mixer for a hexacopter in the X configuration. All c
are mixed 100%.
R: 6x 10000 10000 10000 0
+
+Gimbal / payload mixer for last two channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix b/ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix
new file mode 100644
index 0000000000..51cebb7858
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix
@@ -0,0 +1,7 @@
+Multirotor mixer for PX4FMU
+===========================
+
+This file defines a single mixer for a Coaxial Octocopter in the X configuration. All controls
+are mixed 100%.
+
+R: 8c 10000 10000 10000 0
diff --git a/ROMFS/px4fmu_common/mixers/FMU_quad_+.mix b/ROMFS/px4fmu_common/mixers/FMU_quad_+.mix
index dfdf1d58e0..cd9a9cfab6 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_quad_+.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_quad_+.mix
@@ -5,3 +5,23 @@ This file defines a single mixer for a quadrotor in the + configuration. All con
are mixed 100%.
R: 4+ 10000 10000 10000 0
+
+
+Gimbal / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_quad_v.mix b/ROMFS/px4fmu_common/mixers/FMU_quad_v.mix
index 2a4a0f3419..520aba6359 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_quad_v.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_quad_v.mix
@@ -5,3 +5,22 @@ This file defines a single mixer for a quadrotor in the V configuration. All co
are mixed 100%.
R: 4v 10000 10000 10000 0
+
+Gimbal / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_quad_w.mix b/ROMFS/px4fmu_common/mixers/FMU_quad_w.mix
index 81b4af30b2..58e6af74ba 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_quad_w.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_quad_w.mix
@@ -4,3 +4,22 @@ Multirotor mixer for PX4FMU
This file defines a single mixer for a quadrotor with a wide configuration. All controls are mixed 100%.
R: 4w 10000 10000 10000 0
+
+Gimbal / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_quad_x.mix b/ROMFS/px4fmu_common/mixers/FMU_quad_x.mix
index 12a3bee20c..fa21c80128 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_quad_x.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_quad_x.mix
@@ -5,3 +5,22 @@ This file defines a single mixer for a quadrotor in the X configuration. All co
are mixed 100%.
R: 4x 10000 10000 10000 0
+
+Gimbal / payload mixer for last four channels
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_test/init.d/rc.standalone b/ROMFS/px4fmu_test/init.d/rc.standalone
new file mode 100644
index 0000000000..67e95215b9
--- /dev/null
+++ b/ROMFS/px4fmu_test/init.d/rc.standalone
@@ -0,0 +1,13 @@
+#!nsh
+#
+# Flight startup script for PX4FMU standalone configuration.
+#
+
+echo "[init] doing standalone PX4FMU startup..."
+
+#
+# Start the ORB
+#
+uorb start
+
+echo "[init] startup done"
diff --git a/ROMFS/px4fmu_test/init.d/rcS b/ROMFS/px4fmu_test/init.d/rcS
new file mode 100755
index 0000000000..7f161b053a
--- /dev/null
+++ b/ROMFS/px4fmu_test/init.d/rcS
@@ -0,0 +1,4 @@
+#!nsh
+#
+# PX4FMU startup script for test hackery.
+#
diff --git a/Tools/px4params/.gitignore b/Tools/px4params/.gitignore
new file mode 100644
index 0000000000..73cf39575d
--- /dev/null
+++ b/Tools/px4params/.gitignore
@@ -0,0 +1,2 @@
+parameters.wiki
+parameters.xml
\ No newline at end of file
diff --git a/Tools/px4params/README.md b/Tools/px4params/README.md
new file mode 100644
index 0000000000..a23b447995
--- /dev/null
+++ b/Tools/px4params/README.md
@@ -0,0 +1,9 @@
+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
diff --git a/Tools/px4params/dokuwikiout.py b/Tools/px4params/dokuwikiout.py
new file mode 100644
index 0000000000..33f76b415e
--- /dev/null
+++ b/Tools/px4params/dokuwikiout.py
@@ -0,0 +1,27 @@
+import output
+
+class DokuWikiOutput(output.Output):
+ def Generate(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"
+ return result
diff --git a/Tools/px4params/output.py b/Tools/px4params/output.py
new file mode 100644
index 0000000000..c092468713
--- /dev/null
+++ b/Tools/px4params/output.py
@@ -0,0 +1,5 @@
+class Output(object):
+ def Save(self, groups, fn):
+ data = self.Generate(groups)
+ with open(fn, 'w') as f:
+ f.write(data)
diff --git a/Tools/px4params/parser.py b/Tools/px4params/parser.py
new file mode 100644
index 0000000000..251be672f2
--- /dev/null
+++ b/Tools/px4params/parser.py
@@ -0,0 +1,220 @@
+import sys
+import re
+
+class ParameterGroup(object):
+ """
+ Single parameter group
+ """
+ def __init__(self, name):
+ self.name = name
+ self.params = []
+
+ def AddParameter(self, param):
+ """
+ Add parameter to the group
+ """
+ self.params.append(param)
+
+ def GetName(self):
+ """
+ Get parameter group name
+ """
+ return self.name
+
+ def GetParams(self):
+ """
+ Returns the parsed list of parameters. Every parameter is a Parameter
+ object. Note that returned object is not a copy. Modifications affect
+ state of the parser.
+ """
+ return sorted(self.params,
+ cmp=lambda x, y: cmp(x.GetFieldValue("code"),
+ y.GetFieldValue("code")))
+
+class Parameter(object):
+ """
+ Single parameter
+ """
+
+ # Define sorting order of the fields
+ priority = {
+ "code": 10,
+ "type": 9,
+ "short_desc": 8,
+ "long_desc": 7,
+ "default": 6,
+ "min": 5,
+ "max": 4,
+ # all others == 0 (sorted alphabetically)
+ }
+
+ def __init__(self):
+ self.fields = {}
+
+ def SetField(self, code, value):
+ """
+ Set named field value
+ """
+ self.fields[code] = value
+
+ def GetFieldCodes(self):
+ """
+ Return list of existing field codes in convenient order
+ """
+ return sorted(self.fields.keys(),
+ cmp=lambda x, y: cmp(self.priority.get(y, 0),
+ self.priority.get(x, 0)) or cmp(x, y))
+
+ def GetFieldValue(self, code):
+ """
+ Return value of the given field code or None if not found.
+ """
+ return self.fields.get(code)
+
+class Parser(object):
+ """
+ Parses provided data and stores all found parameters internally.
+ """
+
+ re_split_lines = re.compile(r'[\r\n]+')
+ re_comment_start = re.compile(r'^\/\*\*')
+ re_comment_content = re.compile(r'^\*\s*(.*)')
+ re_comment_tag = re.compile(r'@([a-zA-Z][a-zA-Z0-9_]*)\s*(.*)')
+ re_comment_end = re.compile(r'(.*?)\s*\*\/')
+ re_parameter_definition = re.compile(r'PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*,\s*([^ ,\)]+)\s*\)\s*;')
+ re_cut_type_specifier = re.compile(r'[a-z]+$')
+ re_is_a_number = re.compile(r'^-?[0-9\.]')
+ re_remove_dots = re.compile(r'\.+$')
+
+ valid_tags = set(["min", "max", "group"])
+
+ # Order of parameter groups
+ priority = {
+ # All other groups = 0 (sort alphabetically)
+ "Miscellaneous": -10
+ }
+
+ def __init__(self):
+ self.param_groups = {}
+
+ def GetSupportedExtensions(self):
+ """
+ Returns list of supported file extensions that can be parsed by this
+ parser.
+ """
+ return ["cpp", "c"]
+
+ def Parse(self, contents):
+ """
+ Incrementally parse program contents and append all found parameters
+ to the list.
+ """
+ # This code is essentially a comment-parsing grammar. "state"
+ # represents parser state. It contains human-readable state
+ # names.
+ state = None
+ for line in self.re_split_lines.split(contents):
+ line = line.strip()
+ # Ignore empty lines
+ if line == "":
+ continue
+ if self.re_comment_start.match(line):
+ state = "wait-short"
+ short_desc = None
+ long_desc = None
+ tags = {}
+ elif state is not None and state != "comment-processed":
+ m = self.re_comment_end.search(line)
+ if m:
+ line = m.group(1)
+ last_comment_line = True
+ else:
+ last_comment_line = False
+ m = self.re_comment_content.match(line)
+ if m:
+ comment_content = m.group(1)
+ if comment_content == "":
+ # When short comment ends with empty comment line,
+ # start waiting for the next part - long comment.
+ if state == "wait-short-end":
+ state = "wait-long"
+ else:
+ m = self.re_comment_tag.match(comment_content)
+ if m:
+ tag, desc = m.group(1, 2)
+ tags[tag] = desc
+ current_tag = tag
+ state = "wait-tag-end"
+ elif state == "wait-short":
+ # Store first line of the short description
+ short_desc = comment_content
+ state = "wait-short-end"
+ elif state == "wait-short-end":
+ # Append comment line to the short description
+ short_desc += "\n" + comment_content
+ elif state == "wait-long":
+ # Store first line of the long description
+ long_desc = comment_content
+ state = "wait-long-end"
+ elif state == "wait-long-end":
+ # Append comment line to the long description
+ long_desc += "\n" + comment_content
+ elif state == "wait-tag-end":
+ # Append comment line to the tag text
+ tags[current_tag] += "\n" + comment_content
+ else:
+ raise AssertionError(
+ "Invalid parser state: %s" % state)
+ elif not last_comment_line:
+ # Invalid comment line (inside comment, but not starting with
+ # "*" or "*/". Reset parsed content.
+ state = None
+ if last_comment_line:
+ state = "comment-processed"
+ else:
+ # Non-empty line outside the comment
+ m = self.re_parameter_definition.match(line)
+ if m:
+ tp, code, defval = m.group(1, 2, 3)
+ # Remove trailing type specifier from numbers: 0.1f => 0.1
+ if self.re_is_a_number.match(defval):
+ defval = self.re_cut_type_specifier.sub('', defval)
+ param = Parameter()
+ param.SetField("code", code)
+ param.SetField("short_desc", code)
+ param.SetField("type", tp)
+ param.SetField("default", defval)
+ # If comment was found before the parameter declaration,
+ # inject its data into the newly created parameter.
+ group = "Miscellaneous"
+ if state == "comment-processed":
+ if short_desc is not None:
+ param.SetField("short_desc",
+ self.re_remove_dots.sub('', short_desc))
+ if long_desc is not None:
+ param.SetField("long_desc", long_desc)
+ for tag in tags:
+ if tag == "group":
+ group = tags[tag]
+ elif tag not in self.valid_tags:
+ sys.stderr.write("Skipping invalid"
+ "documentation tag: '%s'\n" % tag)
+ else:
+ param.SetField(tag, tags[tag])
+ # Store the parameter
+ if group not in self.param_groups:
+ self.param_groups[group] = ParameterGroup(group)
+ self.param_groups[group].AddParameter(param)
+ # Reset parsed comment.
+ state = None
+
+ def GetParamGroups(self):
+ """
+ Returns the parsed list of parameters. Every parameter is a Parameter
+ object. Note that returned object is not a copy. Modifications affect
+ state of the parser.
+ """
+ return sorted(self.param_groups.values(),
+ cmp=lambda x, y: cmp(self.priority.get(y.GetName(), 0),
+ self.priority.get(x.GetName(), 0)) or cmp(x.GetName(),
+ y.GetName()))
diff --git a/Tools/px4params/px_process_params.py b/Tools/px4params/px_process_params.py
new file mode 100755
index 0000000000..cdf5aba7c0
--- /dev/null
+++ b/Tools/px4params/px_process_params.py
@@ -0,0 +1,61 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (C) 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# PX4 paramers processor (main executable file)
+#
+# It scans src/ subdirectory of the project, collects all parameters
+# definitions, and outputs list of parameters in XML and DokuWiki formats.
+#
+
+import scanner
+import parser
+import xmlout
+import dokuwikiout
+
+# Initialize parser
+prs = parser.Parser()
+
+# Scan directories, and parse the files
+sc = scanner.Scanner()
+sc.ScanDir("../../src", prs)
+output = prs.GetParamGroups()
+
+# Output into XML
+out = xmlout.XMLOutput()
+out.Save(output, "parameters.xml")
+
+# Output into DokuWiki
+out = dokuwikiout.DokuWikiOutput()
+out.Save(output, "parameters.wiki")
diff --git a/Tools/px4params/scanner.py b/Tools/px4params/scanner.py
new file mode 100644
index 0000000000..b5a1af47c3
--- /dev/null
+++ b/Tools/px4params/scanner.py
@@ -0,0 +1,34 @@
+import os
+import re
+
+class Scanner(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())
+ 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:
+ path = os.path.join(dirname, filename)
+ self.ScanFile(path, parser)
+
+ def ScanFile(self, path, parser):
+ """
+ Scans provided file and passes its contents to the parser using
+ parser.Parse method.
+ """
+ with open(path, 'r') as f:
+ contents = f.read()
+ parser.Parse(contents)
diff --git a/Tools/px4params/xmlout.py b/Tools/px4params/xmlout.py
new file mode 100644
index 0000000000..d56802b158
--- /dev/null
+++ b/Tools/px4params/xmlout.py
@@ -0,0 +1,22 @@
+import output
+from xml.dom.minidom import getDOMImplementation
+
+class XMLOutput(output.Output):
+ def Generate(self, groups):
+ impl = getDOMImplementation()
+ xml_document = impl.createDocument(None, "parameters", None)
+ xml_parameters = xml_document.documentElement
+ for group in groups:
+ xml_group = xml_document.createElement("group")
+ xml_group.setAttribute("name", group.GetName())
+ xml_parameters.appendChild(xml_group)
+ for param in group.GetParams():
+ xml_param = xml_document.createElement("parameter")
+ xml_group.appendChild(xml_param)
+ for code in param.GetFieldCodes():
+ value = param.GetFieldValue(code)
+ xml_field = xml_document.createElement(code)
+ xml_param.appendChild(xml_field)
+ xml_value = xml_document.createTextNode(value)
+ xml_field.appendChild(xml_value)
+ return xml_document.toprettyxml(indent=" ", newl="\n", encoding="utf-8")
diff --git a/Tools/px_mkfw.py b/Tools/px_mkfw.py
index faef9ca335..b598a65a1a 100755
--- a/Tools/px_mkfw.py
+++ b/Tools/px_mkfw.py
@@ -1,7 +1,7 @@
#!/usr/bin/env python
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# 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
@@ -60,7 +60,7 @@ def mkdesc():
proto['description'] = ""
proto['git_identity'] = ""
proto['build_time'] = 0
- proto['image'] = base64.b64encode(bytearray())
+ proto['image'] = bytes()
proto['image_size'] = 0
return proto
@@ -99,12 +99,12 @@ if args.description != None:
if args.git_identity != None:
cmd = " ".join(["git", "--git-dir", args.git_identity + "/.git", "describe", "--always", "--dirty"])
p = subprocess.Popen(cmd, shell=True, stdout=subprocess.PIPE).stdout
- desc['git_identity'] = p.read().strip()
+ desc['git_identity'] = str(p.read().strip())
p.close()
if args.image != None:
f = open(args.image, "rb")
bytes = f.read()
desc['image_size'] = len(bytes)
- desc['image'] = base64.b64encode(zlib.compress(bytes,9))
+ desc['image'] = base64.b64encode(zlib.compress(bytes,9)).decode('utf-8')
print(json.dumps(desc, indent=4))
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py
index d2ebf16987..a2d7d371df 100755
--- a/Tools/px_uploader.py
+++ b/Tools/px_uploader.py
@@ -1,7 +1,7 @@
#!/usr/bin/env python
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# 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
@@ -102,7 +102,7 @@ class firmware(object):
0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d])
- crcpad = bytearray('\xff\xff\xff\xff')
+ crcpad = bytearray(b'\xff\xff\xff\xff')
def __init__(self, path):
@@ -137,34 +137,40 @@ class uploader(object):
'''Uploads a firmware file to the PX FMU bootloader'''
# protocol bytes
- INSYNC = chr(0x12)
- EOC = chr(0x20)
+ INSYNC = b'\x12'
+ EOC = b'\x20'
# reply bytes
- OK = chr(0x10)
- FAILED = chr(0x11)
- INVALID = chr(0x13) # rev3+
+ OK = b'\x10'
+ FAILED = b'\x11'
+ INVALID = b'\x13' # rev3+
# command bytes
- NOP = chr(0x00) # guaranteed to be discarded by the bootloader
- GET_SYNC = chr(0x21)
- GET_DEVICE = chr(0x22)
- CHIP_ERASE = chr(0x23)
- CHIP_VERIFY = chr(0x24) # rev2 only
- PROG_MULTI = chr(0x27)
- READ_MULTI = chr(0x28) # rev2 only
- GET_CRC = chr(0x29) # rev3+
- REBOOT = chr(0x30)
+ NOP = b'\x00' # guaranteed to be discarded by the bootloader
+ GET_SYNC = b'\x21'
+ GET_DEVICE = b'\x22'
+ CHIP_ERASE = b'\x23'
+ CHIP_VERIFY = b'\x24' # rev2 only
+ PROG_MULTI = b'\x27'
+ READ_MULTI = b'\x28' # rev2 only
+ GET_CRC = b'\x29' # rev3+
+ REBOOT = b'\x30'
- INFO_BL_REV = chr(1) # bootloader protocol revision
+ INFO_BL_REV = b'\x01' # bootloader protocol revision
BL_REV_MIN = 2 # minimum supported bootloader protocol
- BL_REV_MAX = 3 # maximum supported bootloader protocol
- INFO_BOARD_ID = chr(2) # board type
- INFO_BOARD_REV = chr(3) # board revision
- INFO_FLASH_SIZE = chr(4) # max firmware size in bytes
+ BL_REV_MAX = 4 # maximum supported bootloader protocol
+ INFO_BOARD_ID = b'\x02' # board type
+ INFO_BOARD_REV = b'\x03' # board revision
+ INFO_FLASH_SIZE = b'\x04' # max firmware size in bytes
PROG_MULTI_MAX = 60 # protocol max is 255, must be multiple of 4
READ_MULTI_MAX = 60 # protocol max is 255, something overflows with >= 64
+
+ NSH_INIT = bytearray(b'\x0d\x0d\x0d')
+ NSH_REBOOT_BL = b"reboot -b\n"
+ NSH_REBOOT = b"reboot\n"
+ MAVLINK_REBOOT_ID1 = bytearray(b'\xfe\x21\x72\xff\x00\x4c\x00\x00\x80\x3f\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf6\x00\x01\x00\x00\x48\xf0')
+ MAVLINK_REBOOT_ID0 = bytearray(b'\xfe\x21\x45\xff\x00\x4c\x00\x00\x80\x3f\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf6\x00\x00\x00\x00\xd7\xac')
def __init__(self, portname, baudrate):
# open the port, keep the default timeout short so we can poll quickly
@@ -176,7 +182,7 @@ class uploader(object):
def __send(self, c):
# print("send " + binascii.hexlify(c))
- self.port.write(str(c))
+ self.port.write(c)
def __recv(self, count=1):
c = self.port.read(count)
@@ -192,9 +198,9 @@ class uploader(object):
def __getSync(self):
self.port.flush()
- c = self.__recv()
- if c is not self.INSYNC:
- raise RuntimeError("unexpected 0x%x instead of INSYNC" % ord(c))
+ c = bytes(self.__recv())
+ if c != self.INSYNC:
+ raise RuntimeError("unexpected %s instead of INSYNC" % c)
c = self.__recv()
if c == self.INVALID:
raise RuntimeError("bootloader reports INVALID OPERATION")
@@ -249,17 +255,29 @@ class uploader(object):
# send a PROG_MULTI command to write a collection of bytes
def __program_multi(self, data):
- self.__send(uploader.PROG_MULTI
- + chr(len(data)))
+
+ if runningPython3 == True:
+ length = len(data).to_bytes(1, byteorder='big')
+ else:
+ length = chr(len(data))
+
+ self.__send(uploader.PROG_MULTI)
+ self.__send(length)
self.__send(data)
self.__send(uploader.EOC)
self.__getSync()
# verify multiple bytes in flash
def __verify_multi(self, data):
- self.__send(uploader.READ_MULTI
- + chr(len(data))
- + uploader.EOC)
+
+ if runningPython3 == True:
+ length = len(data).to_bytes(1, byteorder='big')
+ else:
+ length = chr(len(data))
+
+ self.__send(uploader.READ_MULTI)
+ self.__send(length)
+ self.__send(uploader.EOC)
self.port.flush()
programmed = self.__recv(len(data))
if programmed != data:
@@ -350,7 +368,24 @@ class uploader(object):
print("done, rebooting.")
self.__reboot()
self.port.close()
+
+ def send_reboot(self):
+ # try reboot via NSH first
+ self.__send(uploader.NSH_INIT)
+ self.__send(uploader.NSH_REBOOT_BL)
+ self.__send(uploader.NSH_INIT)
+ self.__send(uploader.NSH_REBOOT)
+ # then try MAVLINK command
+ self.__send(uploader.MAVLINK_REBOOT_ID1)
+ self.__send(uploader.MAVLINK_REBOOT_ID0)
+
+
+# Detect python version
+if sys.version_info[0] < 3:
+ runningPython3 = False
+else:
+ runningPython3 = True
# Parse commandline arguments
parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
@@ -365,7 +400,19 @@ print("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property(
# Spin waiting for a device to show up
while True:
- for port in args.port.split(","):
+ portlist = []
+ patterns = args.port.split(",")
+ # on unix-like platforms use glob to support wildcard ports. This allows
+ # the use of /dev/serial/by-id/usb-3D_Robotics on Linux, which prevents the upload from
+ # causing modem hangups etc
+ if "linux" in _platform or "darwin" in _platform:
+ import glob
+ for pattern in patterns:
+ portlist += glob.glob(pattern)
+ else:
+ portlist = patterns
+
+ for port in portlist:
#print("Trying %s" % port)
@@ -383,7 +430,7 @@ while True:
# Windows, don't open POSIX ports
if not "/" in port:
up = uploader(port, args.baud)
- except:
+ except Exception:
# open failed, rate-limit our attempts
time.sleep(0.05)
@@ -396,8 +443,12 @@ while True:
up.identify()
print("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port))
- except:
- # most probably a timeout talking to the port, no bootloader
+ except Exception:
+ # most probably a timeout talking to the port, no bootloader, try to reboot the board
+ print("attempting reboot on %s..." % port)
+ up.send_reboot()
+ # wait for the reboot, without we might run into Serial I/O Error 5
+ time.sleep(0.5)
continue
try:
diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py
index 7fefc5908f..5b1e55e22a 100644
--- a/Tools/sdlog2_dump.py
+++ b/Tools/sdlog2_dump.py
@@ -25,8 +25,12 @@ import struct, sys
if sys.hexversion >= 0x030000F0:
runningPython3 = True
+ def _parseCString(cstr):
+ return str(cstr, 'ascii').split('\0')[0]
else:
runningPython3 = False
+ def _parseCString(cstr):
+ return str(cstr).split('\0')[0]
class SDLog2Parser:
BLOCK_SIZE = 8192
@@ -175,9 +179,9 @@ class SDLog2Parser:
self.__csv_columns.append(full_label)
self.__csv_data[full_label] = None
if self.__file != None:
- print(self.__csv_delim.join(self.__csv_columns), file=self.__file)
+ print(self.__csv_delim.join(self.__csv_columns), file=self.__file)
else:
- print(self.__csv_delim.join(self.__csv_columns))
+ print(self.__csv_delim.join(self.__csv_columns))
def __printCSVRow(self):
s = []
@@ -190,9 +194,9 @@ class SDLog2Parser:
s.append(v)
if self.__file != None:
- print(self.__csv_delim.join(s), file=self.__file)
+ print(self.__csv_delim.join(s), file=self.__file)
else:
- print(self.__csv_delim.join(s))
+ print(self.__csv_delim.join(s))
def __parseMsgDescr(self):
if runningPython3:
@@ -202,14 +206,9 @@ class SDLog2Parser:
msg_type = data[0]
if msg_type != self.MSG_TYPE_FORMAT:
msg_length = data[1]
- if runningPython3:
- msg_name = str(data[2], 'ascii').strip("\0")
- msg_format = str(data[3], 'ascii').strip("\0")
- msg_labels = str(data[4], 'ascii').strip("\0").split(",")
- else:
- msg_name = str(data[2]).strip("\0")
- msg_format = str(data[3]).strip("\0")
- msg_labels = str(data[4]).strip("\0").split(",")
+ msg_name = _parseCString(data[2])
+ msg_format = _parseCString(data[3])
+ msg_labels = _parseCString(data[4]).split(",")
# Convert msg_format to struct.unpack format string
msg_struct = ""
msg_mults = []
@@ -243,7 +242,7 @@ class SDLog2Parser:
data = list(struct.unpack(msg_struct, str(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])))
for i in range(len(data)):
if type(data[i]) is str:
- data[i] = data[i].strip("\0")
+ data[i] = _parseCString(data[i])
m = msg_mults[i]
if m != None:
data[i] = data[i] * m
diff --git a/Tools/tests-host/.gitignore b/Tools/tests-host/.gitignore
new file mode 100644
index 0000000000..61e0915515
--- /dev/null
+++ b/Tools/tests-host/.gitignore
@@ -0,0 +1,2 @@
+./obj/*
+mixer_test
diff --git a/Tools/tests-host/Makefile b/Tools/tests-host/Makefile
new file mode 100644
index 0000000000..97410ff47c
--- /dev/null
+++ b/Tools/tests-host/Makefile
@@ -0,0 +1,39 @@
+
+CC=g++
+CFLAGS=-I. -I../../src/modules -I ../../src/include -I../../src/drivers -I../../src -D__EXPORT="" -Dnullptr="0"
+
+ODIR=obj
+LDIR =../lib
+
+LIBS=-lm
+
+#_DEPS = test.h
+#DEPS = $(patsubst %,$(IDIR)/%,$(_DEPS))
+
+_OBJ = mixer_test.o test_mixer.o mixer_simple.o mixer_multirotor.o mixer.o mixer_group.o mixer_load.o
+OBJ = $(patsubst %,$(ODIR)/%,$(_OBJ))
+
+#$(DEPS)
+$(ODIR)/%.o: %.cpp
+ $(CC) -c -o $@ $< $(CFLAGS)
+
+$(ODIR)/%.o: ../../src/systemcmds/tests/%.cpp
+ $(CC) -c -o $@ $< $(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/mixer/%.c
+ $(CC) -c -o $@ $< $(CFLAGS)
+
+#
+mixer_test: $(OBJ)
+ g++ -o $@ $^ $(CFLAGS) $(LIBS)
+
+.PHONY: clean
+
+clean:
+ rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~
\ No newline at end of file
diff --git a/Tools/tests-host/arch/board/board.h b/Tools/tests-host/arch/board/board.h
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/Tools/tests-host/mixer_test.cpp b/Tools/tests-host/mixer_test.cpp
new file mode 100644
index 0000000000..042322aadc
--- /dev/null
+++ b/Tools/tests-host/mixer_test.cpp
@@ -0,0 +1,12 @@
+#include
+#include
+#include "../../src/systemcmds/tests/tests.h"
+
+int main(int argc, char *argv[]) {
+ warnx("Host execution started");
+
+ char* args[] = {argv[0], "../../ROMFS/px4fmu_common/mixers/IO_pass.mix",
+ "../../ROMFS/px4fmu_common/mixers/FMU_quad_w.mix"};
+
+ test_mixer(3, args);
+}
\ No newline at end of file
diff --git a/Tools/tests-host/nuttx/config.h b/Tools/tests-host/nuttx/config.h
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/makefiles/board_px4fmu-v2.mk b/makefiles/board_px4fmu-v2.mk
new file mode 100644
index 0000000000..e9a2985b7f
--- /dev/null
+++ b/makefiles/board_px4fmu-v2.mk
@@ -0,0 +1,11 @@
+#
+# Board-specific definitions for the PX4FMUv2
+#
+
+#
+# Configure the toolchain
+#
+CONFIG_ARCH = CORTEXM4F
+CONFIG_BOARD = PX4FMU_V2
+
+include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
diff --git a/makefiles/board_px4io-v2.mk b/makefiles/board_px4io-v2.mk
new file mode 100644
index 0000000000..50a4068fb2
--- /dev/null
+++ b/makefiles/board_px4io-v2.mk
@@ -0,0 +1,11 @@
+#
+# Board-specific definitions for the PX4IOv2
+#
+
+#
+# Configure the toolchain
+#
+CONFIG_ARCH = CORTEXM3
+CONFIG_BOARD = PX4IO_V2
+
+include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index 27543e8bbe..3068270865 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -6,6 +6,7 @@
# Use the configuration's ROMFS.
#
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
+ROMFS_OPTIONAL_FILES = $(PX4_BASE)/Images/px4io-v1_default.bin
#
# Board support modules
@@ -17,7 +18,7 @@ MODULES += drivers/stm32/tone_alarm
MODULES += drivers/led
MODULES += drivers/px4io
MODULES += drivers/px4fmu
-MODULES += drivers/boards/px4fmu
+MODULES += drivers/boards/px4fmu-v1
MODULES += drivers/ardrone_interface
MODULES += drivers/l3gd20
MODULES += drivers/bma180
@@ -30,8 +31,9 @@ MODULES += drivers/hil
MODULES += drivers/hott/hott_telemetry
MODULES += drivers/hott/hott_sensors
MODULES += drivers/blinkm
+MODULES += drivers/rgbled
MODULES += drivers/mkblctrl
-MODULES += drivers/md25
+MODULES += drivers/roboclaw
MODULES += drivers/airspeed
MODULES += drivers/ets_airspeed
MODULES += drivers/meas_airspeed
@@ -50,15 +52,18 @@ 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/tests
MODULES += systemcmds/config
+MODULES += systemcmds/nshterm
#
# General system control
#
MODULES += modules/commander
+MODULES += modules/navigator
MODULES += modules/mavlink
MODULES += modules/mavlink_onboard
MODULES += modules/gpio_led
@@ -67,21 +72,17 @@ MODULES += modules/gpio_led
# Estimation modules (EKF / other filters)
#
MODULES += modules/attitude_estimator_ekf
-MODULES += modules/attitude_estimator_so3_comp
-MODULES += modules/position_estimator
MODULES += modules/att_pos_estimator_ekf
+MODULES += modules/position_estimator_inav
MODULES += examples/flow_position_estimator
#
# Vehicle Control
#
-MODULES += modules/segway
-MODULES += modules/fixedwing_backside
-MODULES += modules/fixedwing_att_control
-MODULES += modules/fixedwing_pos_control
-MODULES += modules/fw_att_control_vector
+#MODULES += modules/segway # XXX Needs GCC 4.7 fix
+MODULES += modules/fw_pos_control_l1
+MODULES += modules/fw_att_control
MODULES += modules/multirotor_att_control
-MODULES += modules/mc_att_control_vector
MODULES += modules/multirotor_pos_control
MODULES += examples/flow_position_control
MODULES += examples/flow_speed_control
@@ -91,20 +92,30 @@ MODULES += examples/flow_speed_control
#
MODULES += modules/sdlog2
+#
+# Unit tests
+#
+#MODULES += modules/unit_test
+#MODULES += modules/commander/commander_tests
+
#
# Library modules
#
MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
-MODULES += modules/mathlib
-MODULES += modules/mathlib/math/filter
MODULES += modules/controllib
MODULES += modules/uORB
#
# Libraries
#
-LIBRARIES += modules/mathlib/CMSIS
+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
#
# Demo apps
@@ -124,7 +135,10 @@ LIBRARIES += modules/mathlib/CMSIS
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
-MODULES += examples/fixedwing_control
+#MODULES += examples/fixedwing_control
+
+# Hardware test
+#MODULES += examples/hwtest
#
# Transitional support - add commands from the NuttX export archive.
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
new file mode 100644
index 0000000000..761fb8d9d6
--- /dev/null
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -0,0 +1,155 @@
+#
+# Makefile for the px4fmu_default configuration
+#
+
+#
+# Use the configuration's ROMFS, copy the px4iov2 firmware into
+# the ROMFS if it's available
+#
+ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
+ROMFS_OPTIONAL_FILES = $(PX4_BASE)/Images/px4io-v2_default.bin
+
+#
+# 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/px4io
+MODULES += drivers/boards/px4fmu-v2
+MODULES += drivers/rgbled
+MODULES += drivers/lsm303d
+MODULES += drivers/l3gd20
+MODULES += drivers/hmc5883
+MODULES += drivers/ms5611
+MODULES += drivers/mb12xx
+MODULES += drivers/gps
+MODULES += drivers/hil
+MODULES += drivers/hott/hott_telemetry
+MODULES += drivers/hott/hott_sensors
+MODULES += drivers/blinkm
+MODULES += drivers/roboclaw
+MODULES += drivers/airspeed
+MODULES += drivers/ets_airspeed
+MODULES += drivers/meas_airspeed
+MODULES += modules/sensors
+
+# Needs to be burned to the ground and re-written; for now,
+# just don't build it.
+#MODULES += drivers/mkblctrl
+
+#
+# System commands
+#
+MODULES += systemcmds/ramtron
+MODULES += systemcmds/bl_update
+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/tests
+MODULES += systemcmds/config
+MODULES += systemcmds/nshterm
+
+#
+# General system control
+#
+MODULES += modules/commander
+MODULES += modules/navigator
+MODULES += modules/mavlink
+MODULES += modules/mavlink_onboard
+
+#
+# Estimation modules (EKF / other filters)
+#
+MODULES += modules/attitude_estimator_ekf
+MODULES += modules/att_pos_estimator_ekf
+MODULES += modules/position_estimator_inav
+MODULES += examples/flow_position_estimator
+
+#
+# Vehicle Control
+#
+#MODULES += modules/segway # XXX Needs GCC 4.7 fix
+MODULES += modules/fw_pos_control_l1
+MODULES += modules/fw_att_control
+MODULES += modules/multirotor_att_control
+MODULES += modules/multirotor_pos_control
+
+#
+# Logging
+#
+MODULES += modules/sdlog2
+
+#
+# Unit tests
+#
+#MODULES += modules/unit_test
+#MODULES += modules/commander/commander_tests
+
+#
+# Library modules
+#
+MODULES += modules/systemlib
+MODULES += modules/systemlib/mixer
+MODULES += modules/controllib
+MODULES += modules/uORB
+
+#
+# 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
+
+#
+# Demo apps
+#
+#MODULES += examples/math_demo
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/hello_sky
+MODULES += examples/px4_simple_app
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/daemon
+#MODULES += examples/px4_daemon_app
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/debug_values
+#MODULES += examples/px4_mavlink_debug
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
+#MODULES += examples/fixedwing_control
+
+# Hardware test
+#MODULES += examples/hwtest
+
+#
+# Transitional support - add commands from the NuttX export archive.
+#
+# In general, these should move to modules over time.
+#
+# Each entry here is ... but we use a helper macro
+# to make the table a bit more readable.
+#
+define _B
+ $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
+endef
+
+# command priority stack entrypoint
+BUILTIN_COMMANDS := \
+ $(call _B, sercon, , 2048, sercon_main ) \
+ $(call _B, serdis, , 2048, serdis_main )
diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk
new file mode 100644
index 0000000000..0f60e88b5e
--- /dev/null
+++ b/makefiles/config_px4fmu-v2_test.mk
@@ -0,0 +1,41 @@
+#
+# Makefile for the px4fmu_default configuration
+#
+
+#
+# Use the configuration's ROMFS.
+#
+ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_test
+
+#
+# Board support modules
+#
+MODULES += drivers/device
+MODULES += drivers/stm32
+MODULES += drivers/led
+MODULES += drivers/boards/px4fmu-v2
+MODULES += systemcmds/perf
+MODULES += systemcmds/reboot
+
+#
+# Library modules
+#
+MODULES += modules/systemlib
+MODULES += modules/uORB
+
+#
+# Transitional support - add commands from the NuttX export archive.
+#
+# In general, these should move to modules over time.
+#
+# Each entry here is ... but we use a helper macro
+# to make the table a bit more readable.
+#
+define _B
+ $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
+endef
+
+# command priority stack entrypoint
+BUILTIN_COMMANDS := \
+ $(call _B, sercon, , 2048, sercon_main ) \
+ $(call _B, serdis, , 2048, serdis_main )
diff --git a/makefiles/config_px4io-v1_default.mk b/makefiles/config_px4io-v1_default.mk
index cf70391bcf..73f8adf202 100644
--- a/makefiles/config_px4io-v1_default.mk
+++ b/makefiles/config_px4io-v1_default.mk
@@ -6,5 +6,5 @@
# Board support modules
#
MODULES += drivers/stm32
-MODULES += drivers/boards/px4io
+MODULES += drivers/boards/px4io-v1
MODULES += modules/px4iofirmware
\ No newline at end of file
diff --git a/makefiles/config_px4io-v2_default.mk b/makefiles/config_px4io-v2_default.mk
new file mode 100644
index 0000000000..dbeaba3d37
--- /dev/null
+++ b/makefiles/config_px4io-v2_default.mk
@@ -0,0 +1,10 @@
+#
+# Makefile for the px4iov2_default configuration
+#
+
+#
+# Board support modules
+#
+MODULES += drivers/stm32
+MODULES += drivers/boards/px4io-v2
+MODULES += modules/px4iofirmware
\ No newline at end of file
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
index ecff77db9a..cb20d9cd19 100644
--- a/makefiles/firmware.mk
+++ b/makefiles/firmware.mk
@@ -110,6 +110,8 @@ ifneq ($(words $(PX4_BASE)),1)
$(error Cannot build when the PX4_BASE path contains one or more space characters.)
endif
+$(info % GIT_DESC = $(GIT_DESC))
+
#
# Set a default target so that included makefiles or errors here don't
# cause confusion.
@@ -177,6 +179,17 @@ GLOBAL_DEPS += $(MAKEFILE_LIST)
#
EXTRA_CLEANS =
+
+#
+# Extra defines for compilation
+#
+export EXTRADEFINES := -DGIT_VERSION=$(GIT_DESC)
+
+#
+# Append the per-board driver directory to the header search path.
+#
+INCLUDE_DIRS += $(PX4_MODULE_SRC)drivers/boards/$(BOARD)
+
################################################################################
# NuttX libraries and paths
################################################################################
@@ -317,7 +330,7 @@ endif
# a root from several templates. That would be a nice feature.
#
-# Add dependencies on anything in the ROMFS root
+# Add dependencies on anything in the ROMFS root directory
ROMFS_FILES += $(wildcard \
$(ROMFS_ROOT)/* \
$(ROMFS_ROOT)/*/* \
@@ -329,7 +342,14 @@ ifeq ($(ROMFS_FILES),)
$(error ROMFS_ROOT $(ROMFS_ROOT) specifies a directory containing no files)
endif
ROMFS_DEPS += $(ROMFS_FILES)
+
+# Extra files that may be copied into the ROMFS /extras directory
+# ROMFS_EXTRA_FILES are required, ROMFS_OPTIONAL_FILES are optional
+ROMFS_EXTRA_FILES += $(wildcard $(ROMFS_OPTIONAL_FILES))
+ROMFS_DEPS += $(ROMFS_EXTRA_FILES)
+
ROMFS_IMG = romfs.img
+ROMFS_SCRATCH = romfs_scratch
ROMFS_CSRC = $(ROMFS_IMG:.img=.c)
ROMFS_OBJ = $(ROMFS_CSRC:.c=.o)
LIBS += $(ROMFS_OBJ)
@@ -340,9 +360,18 @@ $(ROMFS_OBJ): $(ROMFS_IMG) $(GLOBAL_DEPS)
$(call BIN_TO_OBJ,$<,$@,romfs_img)
# Generate the ROMFS image from the root
-$(ROMFS_IMG): $(ROMFS_DEPS) $(GLOBAL_DEPS)
+$(ROMFS_IMG): $(ROMFS_SCRATCH) $(ROMFS_DEPS) $(GLOBAL_DEPS)
@$(ECHO) "ROMFS: $@"
- $(Q) $(GENROMFS) -f $@ -d $(ROMFS_ROOT) -V "NSHInitVol"
+ $(Q) $(GENROMFS) -f $@ -d $(ROMFS_SCRATCH) -V "NSHInitVol"
+
+# Construct the ROMFS scratch root from the canonical root
+$(ROMFS_SCRATCH): $(ROMFS_DEPS) $(GLOBAL_DEPS)
+ $(Q) $(MKDIR) -p $(ROMFS_SCRATCH)
+ $(Q) $(COPYDIR) $(ROMFS_ROOT)/* $(ROMFS_SCRATCH)
+ifneq ($(ROMFS_EXTRA_FILES),)
+ $(Q) $(MKDIR) -p $(ROMFS_SCRATCH)/extras
+ $(Q) $(COPY) $(ROMFS_EXTRA_FILES) $(ROMFS_SCRATCH)/extras
+endif
EXTRA_CLEANS += $(ROMGS_OBJ) $(ROMFS_IMG)
diff --git a/makefiles/setup.mk b/makefiles/setup.mk
index 168e41a5cb..183b143d6c 100644
--- a/makefiles/setup.mk
+++ b/makefiles/setup.mk
@@ -43,6 +43,7 @@
#
export PX4_INCLUDE_DIR = $(abspath $(PX4_BASE)/src/include)/
export PX4_MODULE_SRC = $(abspath $(PX4_BASE)/src)/
+export PX4_LIB_DIR = $(abspath $(PX4_BASE)/src/lib)/
export PX4_MK_DIR = $(abspath $(PX4_BASE)/makefiles)/
export NUTTX_SRC = $(abspath $(PX4_BASE)/NuttX/nuttx)/
export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/NuttX/apps)/
@@ -57,7 +58,8 @@ export ARCHIVE_DIR = $(abspath $(PX4_BASE)/Archives)/
#
export INCLUDE_DIRS := $(PX4_MODULE_SRC) \
$(PX4_MODULE_SRC)/modules/ \
- $(PX4_INCLUDE_DIR)
+ $(PX4_INCLUDE_DIR) \
+ $(PX4_LIB_DIR)
#
# Tools
@@ -71,6 +73,7 @@ export RMDIR = rm -rf
export GENROMFS = genromfs
export TOUCH = touch
export MKDIR = mkdir
+export FIND = find
export ECHO = echo
export UNZIP_CMD = unzip
export PYTHON = python
diff --git a/makefiles/upload.mk b/makefiles/upload.mk
index 3aebef8637..bc26d743d0 100644
--- a/makefiles/upload.mk
+++ b/makefiles/upload.mk
@@ -12,13 +12,13 @@ SYSTYPE := $(shell uname -s)
# XXX The uploader should be smarter than this.
#
ifeq ($(SYSTYPE),Darwin)
-SERIAL_PORTS ?= "/dev/tty.usbmodemPX1,/dev/tty.usbmodemPX2,/dev/tty.usbmodemPX3,/dev/tty.usbmodemPX4,/dev/tty.usbmodem1,/dev/tty.usbmodem2,/dev/tty.usbmodem3,/dev/tty.usbmodem4"
+SERIAL_PORTS ?= "/dev/tty.usbmodemPX*,/dev/tty.usbmodem*"
endif
ifeq ($(SYSTYPE),Linux)
-SERIAL_PORTS ?= "/dev/ttyACM5,/dev/ttyACM4,/dev/ttyACM3,/dev/ttyACM2,/dev/ttyACM1,/dev/ttyACM0"
+SERIAL_PORTS ?= "/dev/serial/by-id/usb-3D_Robotics*"
endif
ifeq ($(SERIAL_PORTS),)
-SERIAL_PORTS = "\\\\.\\COM32,\\\\.\\COM31,\\\\.\\COM30,\\\\.\\COM29,\\\\.\\COM28,\\\\.\\COM27,\\\\.\\COM26,\\\\.\\COM25,\\\\.\\COM24,\\\\.\\COM23,\\\\.\\COM22,\\\\.\\COM21,\\\\.\\COM20,\\\\.\\COM19,\\\\.\\COM18,\\\\.\\COM17,\\\\.\\COM16,\\\\.\\COM15,\\\\.\\COM14,\\\\.\\COM13,\\\\.\\COM12,\\\\.\\COM11,\\\\.\\COM10,\\\\.\\COM9,\\\\.\\COM8,\\\\.\\COM7,\\\\.\\COM6,\\\\.\\COM5,\\\\.\\COM4,\\\\.\\COM3,\\\\.\\COM2,\\\\.\\COM1,\\\\.\\COM0"
+SERIAL_PORTS = "COM32,COM31,COM30,COM29,COM28,COM27,COM26,COM25,COM24,COM23,COM22,COM21,COM20,COM19,COM18,COM17,COM16,COM15,COM14,COM13,COM12,COM11,COM10,COM9,COM8,COM7,COM6,COM5,COM4,COM3,COM2,COM1,COM0"
endif
.PHONY: all upload-$(METHOD)-$(BOARD)
@@ -27,6 +27,8 @@ all: upload-$(METHOD)-$(BOARD)
upload-serial-px4fmu-v1: $(BUNDLE) $(UPLOADER)
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
+upload-serial-px4fmu-v2: $(BUNDLE) $(UPLOADER)
+ $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
#
# JTAG firmware uploading with OpenOCD
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
index eec9a89c50..3aad8e6785 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
@@ -12,15 +12,15 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
+#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 0, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 111, 21, 21, 144, 1, 234, 73, 181, 22, 83, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 0, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
#include "../protocol.h"
@@ -74,6 +74,7 @@ enum MAV_CMD
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */
MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */
MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
@@ -86,7 +87,8 @@ enum MAV_CMD
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
- MAV_CMD_ENUM_END=401, /* | */
+ MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
+ MAV_CMD_ENUM_END=501, /* | */
};
#endif
@@ -179,6 +181,7 @@ enum LIMIT_MODULE
#include "./mavlink_msg_data64.h"
#include "./mavlink_msg_data96.h"
#include "./mavlink_msg_rangefinder.h"
+#include "./mavlink_msg_airspeed_autocal.h"
#ifdef __cplusplus
}
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h
index d9d2ccb041..c3ead11401 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t componen
* @brief Pack a ahrs message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param omegaIx X gyro drift estimate rad/s
* @param omegaIy Y gyro drift estimate rad/s
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t com
}
/**
- * @brief Encode a ahrs struct into a message
+ * @brief Encode a ahrs struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t compon
return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
}
+/**
+ * @brief Encode a ahrs 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 ahrs C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ahrs_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
+{
+ return mavlink_msg_ahrs_pack_chan(system_id, component_id, chan, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
+}
+
/**
* @brief Send a ahrs message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h
new file mode 100644
index 0000000000..d046f2ad09
--- /dev/null
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h
@@ -0,0 +1,419 @@
+// MESSAGE AIRSPEED_AUTOCAL PACKING
+
+#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL 174
+
+typedef struct __mavlink_airspeed_autocal_t
+{
+ float vx; ///< GPS velocity north m/s
+ float vy; ///< GPS velocity east m/s
+ float vz; ///< GPS velocity down m/s
+ float diff_pressure; ///< Differential pressure pascals
+ float EAS2TAS; ///< Estimated to true airspeed ratio
+ float ratio; ///< Airspeed ratio
+ float state_x; ///< EKF state x
+ float state_y; ///< EKF state y
+ float state_z; ///< EKF state z
+ float Pax; ///< EKF Pax
+ float Pby; ///< EKF Pby
+ float Pcz; ///< EKF Pcz
+} mavlink_airspeed_autocal_t;
+
+#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN 48
+#define MAVLINK_MSG_ID_174_LEN 48
+
+#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC 167
+#define MAVLINK_MSG_ID_174_CRC 167
+
+
+
+#define MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL { \
+ "AIRSPEED_AUTOCAL", \
+ 12, \
+ { { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_airspeed_autocal_t, vx) }, \
+ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_airspeed_autocal_t, vy) }, \
+ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_airspeed_autocal_t, vz) }, \
+ { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_airspeed_autocal_t, diff_pressure) }, \
+ { "EAS2TAS", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_airspeed_autocal_t, EAS2TAS) }, \
+ { "ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_airspeed_autocal_t, ratio) }, \
+ { "state_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_airspeed_autocal_t, state_x) }, \
+ { "state_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_airspeed_autocal_t, state_y) }, \
+ { "state_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_airspeed_autocal_t, state_z) }, \
+ { "Pax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_airspeed_autocal_t, Pax) }, \
+ { "Pby", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_airspeed_autocal_t, Pby) }, \
+ { "Pcz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_airspeed_autocal_t, Pcz) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a airspeed_autocal 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 vx GPS velocity north m/s
+ * @param vy GPS velocity east m/s
+ * @param vz GPS velocity down m/s
+ * @param diff_pressure Differential pressure pascals
+ * @param EAS2TAS Estimated to true airspeed ratio
+ * @param ratio Airspeed ratio
+ * @param state_x EKF state x
+ * @param state_y EKF state y
+ * @param state_z EKF state z
+ * @param Pax EKF Pax
+ * @param Pby EKF Pby
+ * @param Pcz EKF Pcz
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airspeed_autocal_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ 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[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
+ _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);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#else
+ mavlink_airspeed_autocal_t packet;
+ 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;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a airspeed_autocal 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 vx GPS velocity north m/s
+ * @param vy GPS velocity east m/s
+ * @param vz GPS velocity down m/s
+ * @param diff_pressure Differential pressure pascals
+ * @param EAS2TAS Estimated to true airspeed ratio
+ * @param ratio Airspeed ratio
+ * @param state_x EKF state x
+ * @param state_y EKF state y
+ * @param state_z EKF state z
+ * @param Pax EKF Pax
+ * @param Pby EKF Pby
+ * @param Pcz EKF Pcz
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airspeed_autocal_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ 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[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
+ _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);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#else
+ mavlink_airspeed_autocal_t packet;
+ 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;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a airspeed_autocal 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 airspeed_autocal C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airspeed_autocal_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal)
+{
+ return mavlink_msg_airspeed_autocal_pack(system_id, component_id, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
+}
+
+/**
+ * @brief Encode a airspeed_autocal 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 airspeed_autocal C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airspeed_autocal_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal)
+{
+ return mavlink_msg_airspeed_autocal_pack_chan(system_id, component_id, chan, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
+}
+
+/**
+ * @brief Send a airspeed_autocal message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param vx GPS velocity north m/s
+ * @param vy GPS velocity east m/s
+ * @param vz GPS velocity down m/s
+ * @param diff_pressure Differential pressure pascals
+ * @param EAS2TAS Estimated to true airspeed ratio
+ * @param ratio Airspeed ratio
+ * @param state_x EKF state x
+ * @param state_y EKF state y
+ * @param state_z EKF state z
+ * @param Pax EKF Pax
+ * @param Pby EKF Pby
+ * @param Pcz EKF Pcz
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_airspeed_autocal_send(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[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
+ _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;
+ 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
+
+// MESSAGE AIRSPEED_AUTOCAL UNPACKING
+
+
+/**
+ * @brief Get field vx from airspeed_autocal message
+ *
+ * @return GPS velocity north m/s
+ */
+static inline float mavlink_msg_airspeed_autocal_get_vx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field vy from airspeed_autocal message
+ *
+ * @return GPS velocity east m/s
+ */
+static inline float mavlink_msg_airspeed_autocal_get_vy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field vz from airspeed_autocal message
+ *
+ * @return GPS velocity down m/s
+ */
+static inline float mavlink_msg_airspeed_autocal_get_vz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field diff_pressure from airspeed_autocal message
+ *
+ * @return Differential pressure pascals
+ */
+static inline float mavlink_msg_airspeed_autocal_get_diff_pressure(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field EAS2TAS from airspeed_autocal message
+ *
+ * @return Estimated to true airspeed ratio
+ */
+static inline float mavlink_msg_airspeed_autocal_get_EAS2TAS(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field ratio from airspeed_autocal message
+ *
+ * @return Airspeed ratio
+ */
+static inline float mavlink_msg_airspeed_autocal_get_ratio(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field state_x from airspeed_autocal message
+ *
+ * @return EKF state x
+ */
+static inline float mavlink_msg_airspeed_autocal_get_state_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field state_y from airspeed_autocal message
+ *
+ * @return EKF state y
+ */
+static inline float mavlink_msg_airspeed_autocal_get_state_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field state_z from airspeed_autocal message
+ *
+ * @return EKF state z
+ */
+static inline float mavlink_msg_airspeed_autocal_get_state_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field Pax from airspeed_autocal message
+ *
+ * @return EKF Pax
+ */
+static inline float mavlink_msg_airspeed_autocal_get_Pax(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field Pby from airspeed_autocal message
+ *
+ * @return EKF Pby
+ */
+static inline float mavlink_msg_airspeed_autocal_get_Pby(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 40);
+}
+
+/**
+ * @brief Get field Pcz from airspeed_autocal message
+ *
+ * @return EKF Pcz
+ */
+static inline float mavlink_msg_airspeed_autocal_get_Pcz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 44);
+}
+
+/**
+ * @brief Decode a airspeed_autocal message into a struct
+ *
+ * @param msg The message to decode
+ * @param airspeed_autocal C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_airspeed_autocal_decode(const mavlink_message_t* msg, mavlink_airspeed_autocal_t* airspeed_autocal)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ airspeed_autocal->vx = mavlink_msg_airspeed_autocal_get_vx(msg);
+ airspeed_autocal->vy = mavlink_msg_airspeed_autocal_get_vy(msg);
+ airspeed_autocal->vz = mavlink_msg_airspeed_autocal_get_vz(msg);
+ airspeed_autocal->diff_pressure = mavlink_msg_airspeed_autocal_get_diff_pressure(msg);
+ airspeed_autocal->EAS2TAS = mavlink_msg_airspeed_autocal_get_EAS2TAS(msg);
+ airspeed_autocal->ratio = mavlink_msg_airspeed_autocal_get_ratio(msg);
+ airspeed_autocal->state_x = mavlink_msg_airspeed_autocal_get_state_x(msg);
+ airspeed_autocal->state_y = mavlink_msg_airspeed_autocal_get_state_y(msg);
+ airspeed_autocal->state_z = mavlink_msg_airspeed_autocal_get_state_z(msg);
+ airspeed_autocal->Pax = mavlink_msg_airspeed_autocal_get_Pax(msg);
+ airspeed_autocal->Pby = mavlink_msg_airspeed_autocal_get_Pby(msg);
+ airspeed_autocal->Pcz = mavlink_msg_airspeed_autocal_get_Pcz(msg);
+#else
+ memcpy(airspeed_autocal, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+}
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h
index c6c7624513..821ce73e47 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t compon
* @brief Pack a ap_adc message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param adc1 ADC output 1
* @param adc2 ADC output 2
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t c
}
/**
- * @brief Encode a ap_adc struct into a message
+ * @brief Encode a ap_adc struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t comp
return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
}
+/**
+ * @brief Encode a ap_adc 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 ap_adc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ap_adc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
+{
+ return mavlink_msg_ap_adc_pack_chan(system_id, component_id, chan, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
+}
+
/**
* @brief Send a ap_adc message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h
index c753585267..9200eefa0d 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_data16_pack(uint8_t system_id, uint8_t compon
* @brief Pack a data16 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type data type
* @param len data length
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_data16_pack_chan(uint8_t system_id, uint8_t c
}
/**
- * @brief Encode a data16 struct into a message
+ * @brief Encode a data16 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_data16_encode(uint8_t system_id, uint8_t comp
return mavlink_msg_data16_pack(system_id, component_id, msg, data16->type, data16->len, data16->data);
}
+/**
+ * @brief Encode a data16 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 data16 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data16_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data16_t* data16)
+{
+ return mavlink_msg_data16_pack_chan(system_id, component_id, chan, msg, data16->type, data16->len, data16->data);
+}
+
/**
* @brief Send a data16 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h
index 46c804a3c2..3afedb7874 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_data32_pack(uint8_t system_id, uint8_t compon
* @brief Pack a data32 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type data type
* @param len data length
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_data32_pack_chan(uint8_t system_id, uint8_t c
}
/**
- * @brief Encode a data32 struct into a message
+ * @brief Encode a data32 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_data32_encode(uint8_t system_id, uint8_t comp
return mavlink_msg_data32_pack(system_id, component_id, msg, data32->type, data32->len, data32->data);
}
+/**
+ * @brief Encode a data32 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 data32 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data32_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data32_t* data32)
+{
+ return mavlink_msg_data32_pack_chan(system_id, component_id, chan, msg, data32->type, data32->len, data32->data);
+}
+
/**
* @brief Send a data32 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h
index 843084dffa..6931ada167 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_data64_pack(uint8_t system_id, uint8_t compon
* @brief Pack a data64 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type data type
* @param len data length
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_data64_pack_chan(uint8_t system_id, uint8_t c
}
/**
- * @brief Encode a data64 struct into a message
+ * @brief Encode a data64 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_data64_encode(uint8_t system_id, uint8_t comp
return mavlink_msg_data64_pack(system_id, component_id, msg, data64->type, data64->len, data64->data);
}
+/**
+ * @brief Encode a data64 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 data64 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data64_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data64_t* data64)
+{
+ return mavlink_msg_data64_pack_chan(system_id, component_id, chan, msg, data64->type, data64->len, data64->data);
+}
+
/**
* @brief Send a data64 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h
index 095628865c..cffc7d7e7f 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_data96_pack(uint8_t system_id, uint8_t compon
* @brief Pack a data96 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type data type
* @param len data length
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_data96_pack_chan(uint8_t system_id, uint8_t c
}
/**
- * @brief Encode a data96 struct into a message
+ * @brief Encode a data96 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_data96_encode(uint8_t system_id, uint8_t comp
return mavlink_msg_data96_pack(system_id, component_id, msg, data96->type, data96->len, data96->data);
}
+/**
+ * @brief Encode a data96 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 data96 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data96_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data96_t* data96)
+{
+ return mavlink_msg_data96_pack_chan(system_id, component_id, chan, msg, data96->type, data96->len, data96->data);
+}
+
/**
* @brief Send a data96 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h
index bcc706a887..c6518c4199 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uin
* @brief Pack a digicam_configure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a digicam_configure struct into a message
+ * @brief Encode a digicam_configure struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -181,6 +181,20 @@ static inline uint16_t mavlink_msg_digicam_configure_encode(uint8_t system_id, u
return mavlink_msg_digicam_configure_pack(system_id, component_id, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
}
+/**
+ * @brief Encode a digicam_configure 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 digicam_configure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_digicam_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure)
+{
+ return mavlink_msg_digicam_configure_pack_chan(system_id, component_id, chan, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
+}
+
/**
* @brief Send a digicam_configure message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h
index 7fa8cdfef8..bfa5414a39 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h
@@ -104,7 +104,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8
* @brief Pack a digicam_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -161,7 +161,7 @@ static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a digicam_control struct into a message
+ * @brief Encode a digicam_control struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -173,6 +173,20 @@ static inline uint16_t mavlink_msg_digicam_control_encode(uint8_t system_id, uin
return mavlink_msg_digicam_control_pack(system_id, component_id, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
}
+/**
+ * @brief Encode a digicam_control struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param digicam_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_digicam_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control)
+{
+ return mavlink_msg_digicam_control_pack_chan(system_id, component_id, chan, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
+}
+
/**
* @brief Send a digicam_control message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h
index 2cd4fc798c..fe3677d53d 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uin
* @brief Pack a fence_fetch_point message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_fence_fetch_point_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a fence_fetch_point struct into a message
+ * @brief Encode a fence_fetch_point struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_fence_fetch_point_encode(uint8_t system_id, u
return mavlink_msg_fence_fetch_point_pack(system_id, component_id, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
}
+/**
+ * @brief Encode a fence_fetch_point 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 fence_fetch_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fence_fetch_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point)
+{
+ return mavlink_msg_fence_fetch_point_pack_chan(system_id, component_id, chan, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
+}
+
/**
* @brief Send a fence_fetch_point message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
index b3c4706ee0..febda6cdc5 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t c
* @brief Pack a fence_point message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint
}
/**
- * @brief Encode a fence_point struct into a message
+ * @brief Encode a fence_point struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t
return mavlink_msg_fence_point_pack(system_id, component_id, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
}
+/**
+ * @brief Encode a fence_point 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 fence_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fence_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point)
+{
+ return mavlink_msg_fence_point_pack_chan(system_id, component_id, chan, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
+}
+
/**
* @brief Send a fence_point message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h
index 32f2bc03a8..6120904061 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t
* @brief Pack a fence_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 was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param breach_status 0 if currently inside fence, 1 if outside
* @param breach_count number of fence breaches
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a fence_status struct into a message
+ * @brief Encode a fence_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_
return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
}
+/**
+ * @brief Encode a fence_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 fence_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fence_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
+{
+ return mavlink_msg_fence_status_pack_chan(system_id, component_id, chan, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
+}
+
/**
* @brief Send a fence_status message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h
index 73870ec0fb..2f5dea513a 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t comp
* @brief Pack a hwstatus message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param Vcc board voltage (mV)
* @param I2Cerr I2C error count
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a hwstatus struct into a message
+ * @brief Encode a hwstatus struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_hwstatus_encode(uint8_t system_id, uint8_t co
return mavlink_msg_hwstatus_pack(system_id, component_id, msg, hwstatus->Vcc, hwstatus->I2Cerr);
}
+/**
+ * @brief Encode a hwstatus 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 hwstatus C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hwstatus_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus)
+{
+ return mavlink_msg_hwstatus_pack_chan(system_id, component_id, chan, msg, hwstatus->Vcc, hwstatus->I2Cerr);
+}
+
/**
* @brief Send a hwstatus message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h
index f7b04fba71..34743fd021 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h
@@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_limits_status_pack(uint8_t system_id, uint8_t
* @brief Pack a limits_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 was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param limits_state state of AP_Limits, (see enum LimitState, LIMITS_STATE)
* @param last_trigger time of last breach in milliseconds since boot
@@ -153,7 +153,7 @@ static inline uint16_t mavlink_msg_limits_status_pack_chan(uint8_t system_id, ui
}
/**
- * @brief Encode a limits_status struct into a message
+ * @brief Encode a limits_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -165,6 +165,20 @@ static inline uint16_t mavlink_msg_limits_status_encode(uint8_t system_id, uint8
return mavlink_msg_limits_status_pack(system_id, component_id, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
}
+/**
+ * @brief Encode a limits_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 limits_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_limits_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_limits_status_t* limits_status)
+{
+ return mavlink_msg_limits_status_pack_chan(system_id, component_id, chan, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
+}
+
/**
* @brief Send a limits_status message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h
index 437029eed7..55f772bbc5 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t compo
* @brief Pack a meminfo message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param brkval heap top
* @param freemem free memory
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a meminfo struct into a message
+ * @brief Encode a meminfo struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t com
return mavlink_msg_meminfo_pack(system_id, component_id, msg, meminfo->brkval, meminfo->freemem);
}
+/**
+ * @brief Encode a meminfo 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 meminfo C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_meminfo_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo)
+{
+ return mavlink_msg_meminfo_pack_chan(system_id, component_id, chan, msg, meminfo->brkval, meminfo->freemem);
+}
+
/**
* @brief Send a meminfo message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h
index 450153c6fe..de717dfa4d 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8
* @brief Pack a mount_configure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a mount_configure struct into a message
+ * @brief Encode a mount_configure struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_mount_configure_encode(uint8_t system_id, uin
return mavlink_msg_mount_configure_pack(system_id, component_id, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
}
+/**
+ * @brief Encode a mount_configure 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 mount_configure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure)
+{
+ return mavlink_msg_mount_configure_pack_chan(system_id, component_id, chan, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
+}
+
/**
* @brief Send a mount_configure message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h
index 5b83d7e970..44416353ed 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t
* @brief Pack a mount_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, ui
}
/**
- * @brief Encode a mount_control struct into a message
+ * @brief Encode a mount_control struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_mount_control_encode(uint8_t system_id, uint8
return mavlink_msg_mount_control_pack(system_id, component_id, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
}
+/**
+ * @brief Encode a mount_control struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param mount_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control)
+{
+ return mavlink_msg_mount_control_pack_chan(system_id, component_id, chan, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
+}
+
/**
* @brief Send a mount_control message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h
index c031db42b4..4905905dc5 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t
* @brief Pack a mount_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 was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a mount_status struct into a message
+ * @brief Encode a mount_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_mount_status_encode(uint8_t system_id, uint8_
return mavlink_msg_mount_status_pack(system_id, component_id, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c);
}
+/**
+ * @brief Encode a mount_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 mount_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status)
+{
+ return mavlink_msg_mount_status_pack_chan(system_id, component_id, chan, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c);
+}
+
/**
* @brief Send a mount_status message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h
index e13776993e..8e9740e828 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone
* @brief Pack a radio message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param rssi local signal strength
* @param remrssi remote signal strength
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co
}
/**
- * @brief Encode a radio struct into a message
+ * @brief Encode a radio struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t compo
return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
}
+/**
+ * @brief Encode a radio 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 radio C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_radio_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_t* radio)
+{
+ return mavlink_msg_radio_pack_chan(system_id, component_id, chan, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
+}
+
/**
* @brief Send a radio message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h
index d88abe36a4..c476447a87 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_rangefinder_pack(uint8_t system_id, uint8_t c
* @brief Pack a rangefinder message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param distance distance in meters
* @param voltage raw voltage if available, zero otherwise
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_rangefinder_pack_chan(uint8_t system_id, uint
}
/**
- * @brief Encode a rangefinder struct into a message
+ * @brief Encode a rangefinder struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_rangefinder_encode(uint8_t system_id, uint8_t
return mavlink_msg_rangefinder_pack(system_id, component_id, msg, rangefinder->distance, rangefinder->voltage);
}
+/**
+ * @brief Encode a rangefinder 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 rangefinder C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rangefinder_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rangefinder_t* rangefinder)
+{
+ return mavlink_msg_rangefinder_pack_chan(system_id, component_id, chan, msg, rangefinder->distance, rangefinder->voltage);
+}
+
/**
* @brief Send a rangefinder message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h
index d121e48e66..31b7d989de 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h
@@ -114,7 +114,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_
* @brief Pack a sensor_offsets message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
@@ -177,7 +177,7 @@ static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, u
}
/**
- * @brief Encode a sensor_offsets struct into a message
+ * @brief Encode a sensor_offsets struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -189,6 +189,20 @@ static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint
return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
}
+/**
+ * @brief Encode a sensor_offsets 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 sensor_offsets C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sensor_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
+{
+ return mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, chan, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
+}
+
/**
* @brief Send a sensor_offsets message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h
index a59e906494..b2c629c39a 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8
* @brief Pack a set_mag_offsets message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a set_mag_offsets struct into a message
+ * @brief Encode a set_mag_offsets struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uin
return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
}
+/**
+ * @brief Encode a set_mag_offsets 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 set_mag_offsets C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_mag_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
+{
+ return mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, chan, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
+}
+
/**
* @brief Send a set_mag_offsets message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h
index 7373c8bffe..8ef44f76d5 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h
@@ -13,15 +13,15 @@ typedef struct __mavlink_simstate_t
float xgyro; ///< Angular speed around X axis rad/s
float ygyro; ///< Angular speed around Y axis rad/s
float zgyro; ///< Angular speed around Z axis rad/s
- float lat; ///< Latitude in degrees
- float lng; ///< Longitude in degrees
+ int32_t lat; ///< Latitude in degrees * 1E7
+ int32_t lng; ///< Longitude in degrees * 1E7
} mavlink_simstate_t;
#define MAVLINK_MSG_ID_SIMSTATE_LEN 44
#define MAVLINK_MSG_ID_164_LEN 44
-#define MAVLINK_MSG_ID_SIMSTATE_CRC 111
-#define MAVLINK_MSG_ID_164_CRC 111
+#define MAVLINK_MSG_ID_SIMSTATE_CRC 154
+#define MAVLINK_MSG_ID_164_CRC 154
@@ -37,8 +37,8 @@ typedef struct __mavlink_simstate_t
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \
- { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_simstate_t, lat) }, \
- { "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_simstate_t, lng) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_simstate_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_simstate_t, lng) }, \
} \
}
@@ -58,12 +58,12 @@ typedef struct __mavlink_simstate_t
* @param xgyro Angular speed around X axis rad/s
* @param ygyro Angular speed around Y axis rad/s
* @param zgyro Angular speed around Z axis rad/s
- * @param lat Latitude in degrees
- * @param lng Longitude in degrees
+ * @param lat Latitude in degrees * 1E7
+ * @param lng Longitude in degrees * 1E7
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lng)
+ 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[MAVLINK_MSG_ID_SIMSTATE_LEN];
@@ -76,8 +76,8 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
- _mav_put_float(buf, 36, lat);
- _mav_put_float(buf, 40, lng);
+ _mav_put_int32_t(buf, 36, lat);
+ _mav_put_int32_t(buf, 40, lng);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN);
#else
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp
* @brief Pack a simstate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
@@ -120,13 +120,13 @@ static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t comp
* @param xgyro Angular speed around X axis rad/s
* @param ygyro Angular speed around Y axis rad/s
* @param zgyro Angular speed around Z axis rad/s
- * @param lat Latitude in degrees
- * @param lng Longitude in degrees
+ * @param lat Latitude in degrees * 1E7
+ * @param lng Longitude in degrees * 1E7
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
- float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lng)
+ 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[MAVLINK_MSG_ID_SIMSTATE_LEN];
@@ -139,8 +139,8 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
- _mav_put_float(buf, 36, lat);
- _mav_put_float(buf, 40, lng);
+ _mav_put_int32_t(buf, 36, lat);
+ _mav_put_int32_t(buf, 40, lng);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN);
#else
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a simstate struct into a message
+ * @brief Encode a simstate struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -181,6 +181,20 @@ static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t co
return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
}
+/**
+ * @brief Encode a simstate 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 simstate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_simstate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_simstate_t* simstate)
+{
+ return mavlink_msg_simstate_pack_chan(system_id, component_id, chan, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
+}
+
/**
* @brief Send a simstate message
* @param chan MAVLink channel to send the message
@@ -194,12 +208,12 @@ static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t co
* @param xgyro Angular speed around X axis rad/s
* @param ygyro Angular speed around Y axis rad/s
* @param zgyro Angular speed around Z axis rad/s
- * @param lat Latitude in degrees
- * @param lng Longitude in degrees
+ * @param lat Latitude in degrees * 1E7
+ * @param lng Longitude in degrees * 1E7
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lng)
+static inline void mavlink_msg_simstate_send(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[MAVLINK_MSG_ID_SIMSTATE_LEN];
@@ -212,8 +226,8 @@ static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll,
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
- _mav_put_float(buf, 36, lat);
- _mav_put_float(buf, 40, lng);
+ _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);
@@ -340,21 +354,21 @@ static inline float mavlink_msg_simstate_get_zgyro(const mavlink_message_t* msg)
/**
* @brief Get field lat from simstate message
*
- * @return Latitude in degrees
+ * @return Latitude in degrees * 1E7
*/
-static inline float mavlink_msg_simstate_get_lat(const mavlink_message_t* msg)
+static inline int32_t mavlink_msg_simstate_get_lat(const mavlink_message_t* msg)
{
- return _MAV_RETURN_float(msg, 36);
+ return _MAV_RETURN_int32_t(msg, 36);
}
/**
* @brief Get field lng from simstate message
*
- * @return Longitude in degrees
+ * @return Longitude in degrees * 1E7
*/
-static inline float mavlink_msg_simstate_get_lng(const mavlink_message_t* msg)
+static inline int32_t mavlink_msg_simstate_get_lng(const mavlink_message_t* msg)
{
- return _MAV_RETURN_float(msg, 40);
+ return _MAV_RETURN_int32_t(msg, 40);
}
/**
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h
index ebdd2949d9..7608a7bd10 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_wind_pack(uint8_t system_id, uint8_t componen
* @brief Pack a wind message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param direction wind direction that wind is coming from (degrees)
* @param speed wind speed in ground plane (m/s)
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_wind_pack_chan(uint8_t system_id, uint8_t com
}
/**
- * @brief Encode a wind struct into a message
+ * @brief Encode a wind struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_wind_encode(uint8_t system_id, uint8_t compon
return mavlink_msg_wind_pack(system_id, component_id, msg, wind->direction, wind->speed, wind->speed_z);
}
+/**
+ * @brief Encode a wind 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 wind C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_wind_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wind_t* wind)
+{
+ return mavlink_msg_wind_pack_chan(system_id, component_id, chan, msg, wind->direction, wind->speed, wind->speed_z);
+}
+
/**
* @brief Send a wind message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h
index 07bf19ee07..2c9cfef3dc 100644
--- a/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h
+++ b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h
@@ -738,8 +738,8 @@ static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavli
185.0,
213.0,
241.0,
- 269.0,
- 297.0,
+ 963499336,
+ 963499544,
};
mavlink_simstate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
@@ -1225,6 +1225,71 @@ static void mavlink_test_rangefinder(uint8_t system_id, uint8_t component_id, ma
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
+static void mavlink_test_airspeed_autocal(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_airspeed_autocal_t packet_in = {
+ 17.0,
+ 45.0,
+ 73.0,
+ 101.0,
+ 129.0,
+ 157.0,
+ 185.0,
+ 213.0,
+ 241.0,
+ 269.0,
+ 297.0,
+ 325.0,
+ };
+ mavlink_airspeed_autocal_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.vx = packet_in.vx;
+ packet1.vy = packet_in.vy;
+ packet1.vz = packet_in.vz;
+ packet1.diff_pressure = packet_in.diff_pressure;
+ packet1.EAS2TAS = packet_in.EAS2TAS;
+ packet1.ratio = packet_in.ratio;
+ packet1.state_x = packet_in.state_x;
+ packet1.state_y = packet_in.state_y;
+ packet1.state_z = packet_in.state_z;
+ packet1.Pax = packet_in.Pax;
+ packet1.Pby = packet_in.Pby;
+ packet1.Pcz = packet_in.Pcz;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airspeed_autocal_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_airspeed_autocal_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airspeed_autocal_pack(system_id, component_id, &msg , packet1.vx , packet1.vy , packet1.vz , packet1.diff_pressure , packet1.EAS2TAS , packet1.ratio , packet1.state_x , packet1.state_y , packet1.state_z , packet1.Pax , packet1.Pby , packet1.Pcz );
+ mavlink_msg_airspeed_autocal_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airspeed_autocal_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.vx , packet1.vy , packet1.vz , packet1.diff_pressure , packet1.EAS2TAS , packet1.ratio , packet1.state_x , packet1.state_y , packet1.state_z , packet1.Pax , packet1.Pby , packet1.Pcz );
+ mavlink_msg_airspeed_autocal_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
@@ -71,7 +96,8 @@ enum MAV_CMD
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
- MAV_CMD_ENUM_END=401, /* | */
+ MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
+ MAV_CMD_ENUM_END=501, /* | */
};
#endif
diff --git a/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h b/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h
index dabccdf733..ed7c86bcb8 100644
--- a/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h
+++ b/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h
@@ -159,7 +159,7 @@ static inline uint16_t mavlink_msg_aq_telemetry_f_pack(uint8_t system_id, uint8_
* @brief Pack a aq_telemetry_f message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param Index Index of message
* @param value1 value1
@@ -249,7 +249,7 @@ static inline uint16_t mavlink_msg_aq_telemetry_f_pack_chan(uint8_t system_id, u
}
/**
- * @brief Encode a aq_telemetry_f struct into a message
+ * @brief Encode a aq_telemetry_f struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -261,6 +261,20 @@ static inline uint16_t mavlink_msg_aq_telemetry_f_encode(uint8_t system_id, uint
return mavlink_msg_aq_telemetry_f_pack(system_id, component_id, msg, aq_telemetry_f->Index, aq_telemetry_f->value1, aq_telemetry_f->value2, aq_telemetry_f->value3, aq_telemetry_f->value4, aq_telemetry_f->value5, aq_telemetry_f->value6, aq_telemetry_f->value7, aq_telemetry_f->value8, aq_telemetry_f->value9, aq_telemetry_f->value10, aq_telemetry_f->value11, aq_telemetry_f->value12, aq_telemetry_f->value13, aq_telemetry_f->value14, aq_telemetry_f->value15, aq_telemetry_f->value16, aq_telemetry_f->value17, aq_telemetry_f->value18, aq_telemetry_f->value19, aq_telemetry_f->value20);
}
+/**
+ * @brief Encode a aq_telemetry_f 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 aq_telemetry_f C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_aq_telemetry_f_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_aq_telemetry_f_t* aq_telemetry_f)
+{
+ return mavlink_msg_aq_telemetry_f_pack_chan(system_id, component_id, chan, msg, aq_telemetry_f->Index, aq_telemetry_f->value1, aq_telemetry_f->value2, aq_telemetry_f->value3, aq_telemetry_f->value4, aq_telemetry_f->value5, aq_telemetry_f->value6, aq_telemetry_f->value7, aq_telemetry_f->value8, aq_telemetry_f->value9, aq_telemetry_f->value10, aq_telemetry_f->value11, aq_telemetry_f->value12, aq_telemetry_f->value13, aq_telemetry_f->value14, aq_telemetry_f->value15, aq_telemetry_f->value16, aq_telemetry_f->value17, aq_telemetry_f->value18, aq_telemetry_f->value19, aq_telemetry_f->value20);
+}
+
/**
* @brief Send a aq_telemetry_f message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/autoquad/version.h b/mavlink/include/mavlink/v1.0/autoquad/version.h
index a26ce2e909..d8ba74f03c 100644
--- a/mavlink/include/mavlink/v1.0/autoquad/version.h
+++ b/mavlink/include/mavlink/v1.0/autoquad/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Thu Jul 4 13:11:37 2013"
+#define MAVLINK_BUILD_DATE "Tue Sep 10 23:49:36 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
diff --git a/mavlink/include/mavlink/v1.0/common/common.h b/mavlink/include/mavlink/v1.0/common/common.h
index e2ab66ed1c..9d3db33265 100644
--- a/mavlink/include/mavlink/v1.0/common/common.h
+++ b/mavlink/include/mavlink/v1.0/common/common.h
@@ -260,6 +260,7 @@ enum MAV_CMD
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
@@ -268,7 +269,8 @@ enum MAV_CMD
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
- MAV_CMD_ENUM_END=401, /* | */
+ MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
+ MAV_CMD_ENUM_END=501, /* | */
};
#endif
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_6dof_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_6dof_setpoint.h
deleted file mode 100644
index 0c4ab8c7df..0000000000
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_6dof_setpoint.h
+++ /dev/null
@@ -1,276 +0,0 @@
-// MESSAGE 6DOF_SETPOINT PACKING
-
-#define MAVLINK_MSG_ID_6DOF_SETPOINT 149
-
-typedef struct __mavlink_6dof_setpoint_t
-{
- float trans_x; ///< Translational Component in x
- float trans_y; ///< Translational Component in y
- float trans_z; ///< Translational Component in z
- float rot_x; ///< Rotational Component in x
- float rot_y; ///< Rotational Component in y
- float rot_z; ///< Rotational Component in z
- uint8_t target_system; ///< System ID
-} mavlink_6dof_setpoint_t;
-
-#define MAVLINK_MSG_ID_6DOF_SETPOINT_LEN 25
-#define MAVLINK_MSG_ID_149_LEN 25
-
-
-
-#define MAVLINK_MESSAGE_INFO_6DOF_SETPOINT { \
- "6DOF_SETPOINT", \
- 7, \
- { { "trans_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_6dof_setpoint_t, trans_x) }, \
- { "trans_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_6dof_setpoint_t, trans_y) }, \
- { "trans_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_6dof_setpoint_t, trans_z) }, \
- { "rot_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_6dof_setpoint_t, rot_x) }, \
- { "rot_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_6dof_setpoint_t, rot_y) }, \
- { "rot_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_6dof_setpoint_t, rot_z) }, \
- { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_6dof_setpoint_t, target_system) }, \
- } \
-}
-
-
-/**
- * @brief Pack a 6dof_setpoint 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 target_system System ID
- * @param trans_x Translational Component in x
- * @param trans_y Translational Component in y
- * @param trans_z Translational Component in z
- * @param rot_x Rotational Component in x
- * @param rot_y Rotational Component in y
- * @param rot_z Rotational Component in z
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_6dof_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[25];
- _mav_put_float(buf, 0, trans_x);
- _mav_put_float(buf, 4, trans_y);
- _mav_put_float(buf, 8, trans_z);
- _mav_put_float(buf, 12, rot_x);
- _mav_put_float(buf, 16, rot_y);
- _mav_put_float(buf, 20, rot_z);
- _mav_put_uint8_t(buf, 24, target_system);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
-#else
- mavlink_6dof_setpoint_t packet;
- packet.trans_x = trans_x;
- packet.trans_y = trans_y;
- packet.trans_z = trans_z;
- packet.rot_x = rot_x;
- packet.rot_y = rot_y;
- packet.rot_z = rot_z;
- packet.target_system = target_system;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_6DOF_SETPOINT;
- return mavlink_finalize_message(msg, system_id, component_id, 25, 144);
-}
-
-/**
- * @brief Pack a 6dof_setpoint message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
- * @param msg The MAVLink message to compress the data into
- * @param target_system System ID
- * @param trans_x Translational Component in x
- * @param trans_y Translational Component in y
- * @param trans_z Translational Component in z
- * @param rot_x Rotational Component in x
- * @param rot_y Rotational Component in y
- * @param rot_z Rotational Component in z
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_6dof_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t target_system,float trans_x,float trans_y,float trans_z,float rot_x,float rot_y,float rot_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[25];
- _mav_put_float(buf, 0, trans_x);
- _mav_put_float(buf, 4, trans_y);
- _mav_put_float(buf, 8, trans_z);
- _mav_put_float(buf, 12, rot_x);
- _mav_put_float(buf, 16, rot_y);
- _mav_put_float(buf, 20, rot_z);
- _mav_put_uint8_t(buf, 24, target_system);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
-#else
- mavlink_6dof_setpoint_t packet;
- packet.trans_x = trans_x;
- packet.trans_y = trans_y;
- packet.trans_z = trans_z;
- packet.rot_x = rot_x;
- packet.rot_y = rot_y;
- packet.rot_z = rot_z;
- packet.target_system = target_system;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_6DOF_SETPOINT;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 144);
-}
-
-/**
- * @brief Encode a 6dof_setpoint struct into a message
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- * @param 6dof_setpoint C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_6dof_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_6dof_setpoint_t* 6dof_setpoint)
-{
- return mavlink_msg_6dof_setpoint_pack(system_id, component_id, msg, 6dof_setpoint->target_system, 6dof_setpoint->trans_x, 6dof_setpoint->trans_y, 6dof_setpoint->trans_z, 6dof_setpoint->rot_x, 6dof_setpoint->rot_y, 6dof_setpoint->rot_z);
-}
-
-/**
- * @brief Send a 6dof_setpoint message
- * @param chan MAVLink channel to send the message
- *
- * @param target_system System ID
- * @param trans_x Translational Component in x
- * @param trans_y Translational Component in y
- * @param trans_z Translational Component in z
- * @param rot_x Rotational Component in x
- * @param rot_y Rotational Component in y
- * @param rot_z Rotational Component in z
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_6dof_setpoint_send(mavlink_channel_t chan, uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[25];
- _mav_put_float(buf, 0, trans_x);
- _mav_put_float(buf, 4, trans_y);
- _mav_put_float(buf, 8, trans_z);
- _mav_put_float(buf, 12, rot_x);
- _mav_put_float(buf, 16, rot_y);
- _mav_put_float(buf, 20, rot_z);
- _mav_put_uint8_t(buf, 24, target_system);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_6DOF_SETPOINT, buf, 25, 144);
-#else
- mavlink_6dof_setpoint_t packet;
- packet.trans_x = trans_x;
- packet.trans_y = trans_y;
- packet.trans_z = trans_z;
- packet.rot_x = rot_x;
- packet.rot_y = rot_y;
- packet.rot_z = rot_z;
- packet.target_system = target_system;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_6DOF_SETPOINT, (const char *)&packet, 25, 144);
-#endif
-}
-
-#endif
-
-// MESSAGE 6DOF_SETPOINT UNPACKING
-
-
-/**
- * @brief Get field target_system from 6dof_setpoint message
- *
- * @return System ID
- */
-static inline uint8_t mavlink_msg_6dof_setpoint_get_target_system(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 24);
-}
-
-/**
- * @brief Get field trans_x from 6dof_setpoint message
- *
- * @return Translational Component in x
- */
-static inline float mavlink_msg_6dof_setpoint_get_trans_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field trans_y from 6dof_setpoint message
- *
- * @return Translational Component in y
- */
-static inline float mavlink_msg_6dof_setpoint_get_trans_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Get field trans_z from 6dof_setpoint message
- *
- * @return Translational Component in z
- */
-static inline float mavlink_msg_6dof_setpoint_get_trans_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field rot_x from 6dof_setpoint message
- *
- * @return Rotational Component in x
- */
-static inline float mavlink_msg_6dof_setpoint_get_rot_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field rot_y from 6dof_setpoint message
- *
- * @return Rotational Component in y
- */
-static inline float mavlink_msg_6dof_setpoint_get_rot_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field rot_z from 6dof_setpoint message
- *
- * @return Rotational Component in z
- */
-static inline float mavlink_msg_6dof_setpoint_get_rot_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Decode a 6dof_setpoint message into a struct
- *
- * @param msg The message to decode
- * @param 6dof_setpoint C-struct to decode the message contents into
- */
-static inline void mavlink_msg_6dof_setpoint_decode(const mavlink_message_t* msg, mavlink_6dof_setpoint_t* 6dof_setpoint)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- 6dof_setpoint->trans_x = mavlink_msg_6dof_setpoint_get_trans_x(msg);
- 6dof_setpoint->trans_y = mavlink_msg_6dof_setpoint_get_trans_y(msg);
- 6dof_setpoint->trans_z = mavlink_msg_6dof_setpoint_get_trans_z(msg);
- 6dof_setpoint->rot_x = mavlink_msg_6dof_setpoint_get_rot_x(msg);
- 6dof_setpoint->rot_y = mavlink_msg_6dof_setpoint_get_rot_y(msg);
- 6dof_setpoint->rot_z = mavlink_msg_6dof_setpoint_get_rot_z(msg);
- 6dof_setpoint->target_system = mavlink_msg_6dof_setpoint_get_target_system(msg);
-#else
- memcpy(6dof_setpoint, _MAV_PAYLOAD(msg), 25);
-#endif
-}
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_8dof_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_8dof_setpoint.h
deleted file mode 100644
index 521d2fb668..0000000000
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_8dof_setpoint.h
+++ /dev/null
@@ -1,320 +0,0 @@
-// MESSAGE 8DOF_SETPOINT PACKING
-
-#define MAVLINK_MSG_ID_8DOF_SETPOINT 148
-
-typedef struct __mavlink_8dof_setpoint_t
-{
- float val1; ///< Value 1
- float val2; ///< Value 2
- float val3; ///< Value 3
- float val4; ///< Value 4
- float val5; ///< Value 5
- float val6; ///< Value 6
- float val7; ///< Value 7
- float val8; ///< Value 8
- uint8_t target_system; ///< System ID
-} mavlink_8dof_setpoint_t;
-
-#define MAVLINK_MSG_ID_8DOF_SETPOINT_LEN 33
-#define MAVLINK_MSG_ID_148_LEN 33
-
-
-
-#define MAVLINK_MESSAGE_INFO_8DOF_SETPOINT { \
- "8DOF_SETPOINT", \
- 9, \
- { { "val1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_8dof_setpoint_t, val1) }, \
- { "val2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_8dof_setpoint_t, val2) }, \
- { "val3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_8dof_setpoint_t, val3) }, \
- { "val4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_8dof_setpoint_t, val4) }, \
- { "val5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_8dof_setpoint_t, val5) }, \
- { "val6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_8dof_setpoint_t, val6) }, \
- { "val7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_8dof_setpoint_t, val7) }, \
- { "val8", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_8dof_setpoint_t, val8) }, \
- { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_8dof_setpoint_t, target_system) }, \
- } \
-}
-
-
-/**
- * @brief Pack a 8dof_setpoint 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 target_system System ID
- * @param val1 Value 1
- * @param val2 Value 2
- * @param val3 Value 3
- * @param val4 Value 4
- * @param val5 Value 5
- * @param val6 Value 6
- * @param val7 Value 7
- * @param val8 Value 8
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_8dof_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[33];
- _mav_put_float(buf, 0, val1);
- _mav_put_float(buf, 4, val2);
- _mav_put_float(buf, 8, val3);
- _mav_put_float(buf, 12, val4);
- _mav_put_float(buf, 16, val5);
- _mav_put_float(buf, 20, val6);
- _mav_put_float(buf, 24, val7);
- _mav_put_float(buf, 28, val8);
- _mav_put_uint8_t(buf, 32, target_system);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33);
-#else
- mavlink_8dof_setpoint_t packet;
- packet.val1 = val1;
- packet.val2 = val2;
- packet.val3 = val3;
- packet.val4 = val4;
- packet.val5 = val5;
- packet.val6 = val6;
- packet.val7 = val7;
- packet.val8 = val8;
- packet.target_system = target_system;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_8DOF_SETPOINT;
- return mavlink_finalize_message(msg, system_id, component_id, 33, 42);
-}
-
-/**
- * @brief Pack a 8dof_setpoint message on a channel
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
- * @param msg The MAVLink message to compress the data into
- * @param target_system System ID
- * @param val1 Value 1
- * @param val2 Value 2
- * @param val3 Value 3
- * @param val4 Value 4
- * @param val5 Value 5
- * @param val6 Value 6
- * @param val7 Value 7
- * @param val8 Value 8
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_8dof_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t target_system,float val1,float val2,float val3,float val4,float val5,float val6,float val7,float val8)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[33];
- _mav_put_float(buf, 0, val1);
- _mav_put_float(buf, 4, val2);
- _mav_put_float(buf, 8, val3);
- _mav_put_float(buf, 12, val4);
- _mav_put_float(buf, 16, val5);
- _mav_put_float(buf, 20, val6);
- _mav_put_float(buf, 24, val7);
- _mav_put_float(buf, 28, val8);
- _mav_put_uint8_t(buf, 32, target_system);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33);
-#else
- mavlink_8dof_setpoint_t packet;
- packet.val1 = val1;
- packet.val2 = val2;
- packet.val3 = val3;
- packet.val4 = val4;
- packet.val5 = val5;
- packet.val6 = val6;
- packet.val7 = val7;
- packet.val8 = val8;
- packet.target_system = target_system;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_8DOF_SETPOINT;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 42);
-}
-
-/**
- * @brief Encode a 8dof_setpoint struct into a message
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param msg The MAVLink message to compress the data into
- * @param 8dof_setpoint C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_8dof_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_8dof_setpoint_t* 8dof_setpoint)
-{
- return mavlink_msg_8dof_setpoint_pack(system_id, component_id, msg, 8dof_setpoint->target_system, 8dof_setpoint->val1, 8dof_setpoint->val2, 8dof_setpoint->val3, 8dof_setpoint->val4, 8dof_setpoint->val5, 8dof_setpoint->val6, 8dof_setpoint->val7, 8dof_setpoint->val8);
-}
-
-/**
- * @brief Send a 8dof_setpoint message
- * @param chan MAVLink channel to send the message
- *
- * @param target_system System ID
- * @param val1 Value 1
- * @param val2 Value 2
- * @param val3 Value 3
- * @param val4 Value 4
- * @param val5 Value 5
- * @param val6 Value 6
- * @param val7 Value 7
- * @param val8 Value 8
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_8dof_setpoint_send(mavlink_channel_t chan, uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[33];
- _mav_put_float(buf, 0, val1);
- _mav_put_float(buf, 4, val2);
- _mav_put_float(buf, 8, val3);
- _mav_put_float(buf, 12, val4);
- _mav_put_float(buf, 16, val5);
- _mav_put_float(buf, 20, val6);
- _mav_put_float(buf, 24, val7);
- _mav_put_float(buf, 28, val8);
- _mav_put_uint8_t(buf, 32, target_system);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_8DOF_SETPOINT, buf, 33, 42);
-#else
- mavlink_8dof_setpoint_t packet;
- packet.val1 = val1;
- packet.val2 = val2;
- packet.val3 = val3;
- packet.val4 = val4;
- packet.val5 = val5;
- packet.val6 = val6;
- packet.val7 = val7;
- packet.val8 = val8;
- packet.target_system = target_system;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_8DOF_SETPOINT, (const char *)&packet, 33, 42);
-#endif
-}
-
-#endif
-
-// MESSAGE 8DOF_SETPOINT UNPACKING
-
-
-/**
- * @brief Get field target_system from 8dof_setpoint message
- *
- * @return System ID
- */
-static inline uint8_t mavlink_msg_8dof_setpoint_get_target_system(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 32);
-}
-
-/**
- * @brief Get field val1 from 8dof_setpoint message
- *
- * @return Value 1
- */
-static inline float mavlink_msg_8dof_setpoint_get_val1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field val2 from 8dof_setpoint message
- *
- * @return Value 2
- */
-static inline float mavlink_msg_8dof_setpoint_get_val2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Get field val3 from 8dof_setpoint message
- *
- * @return Value 3
- */
-static inline float mavlink_msg_8dof_setpoint_get_val3(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field val4 from 8dof_setpoint message
- *
- * @return Value 4
- */
-static inline float mavlink_msg_8dof_setpoint_get_val4(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field val5 from 8dof_setpoint message
- *
- * @return Value 5
- */
-static inline float mavlink_msg_8dof_setpoint_get_val5(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field val6 from 8dof_setpoint message
- *
- * @return Value 6
- */
-static inline float mavlink_msg_8dof_setpoint_get_val6(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field val7 from 8dof_setpoint message
- *
- * @return Value 7
- */
-static inline float mavlink_msg_8dof_setpoint_get_val7(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field val8 from 8dof_setpoint message
- *
- * @return Value 8
- */
-static inline float mavlink_msg_8dof_setpoint_get_val8(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Decode a 8dof_setpoint message into a struct
- *
- * @param msg The message to decode
- * @param 8dof_setpoint C-struct to decode the message contents into
- */
-static inline void mavlink_msg_8dof_setpoint_decode(const mavlink_message_t* msg, mavlink_8dof_setpoint_t* 8dof_setpoint)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- 8dof_setpoint->val1 = mavlink_msg_8dof_setpoint_get_val1(msg);
- 8dof_setpoint->val2 = mavlink_msg_8dof_setpoint_get_val2(msg);
- 8dof_setpoint->val3 = mavlink_msg_8dof_setpoint_get_val3(msg);
- 8dof_setpoint->val4 = mavlink_msg_8dof_setpoint_get_val4(msg);
- 8dof_setpoint->val5 = mavlink_msg_8dof_setpoint_get_val5(msg);
- 8dof_setpoint->val6 = mavlink_msg_8dof_setpoint_get_val6(msg);
- 8dof_setpoint->val7 = mavlink_msg_8dof_setpoint_get_val7(msg);
- 8dof_setpoint->val8 = mavlink_msg_8dof_setpoint_get_val8(msg);
- 8dof_setpoint->target_system = mavlink_msg_8dof_setpoint_get_target_system(msg);
-#else
- memcpy(8dof_setpoint, _MAV_PAYLOAD(msg), 33);
-#endif
-}
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h
index 0ba416ee14..8ddf5bf099 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp
* @brief Pack a attitude message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param roll Roll angle (rad, -pi..+pi)
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a attitude struct into a message
+ * @brief Encode a attitude struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t co
return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
}
+/**
+ * @brief Encode a attitude 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 attitude C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
+{
+ return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
+}
+
/**
* @brief Send a attitude message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h
index 611803f2b7..9f8d587598 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h
@@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u
* @brief Pack a attitude_quaternion message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param q1 Quaternion component 1
@@ -145,7 +145,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_
}
/**
- * @brief Encode a attitude_quaternion struct into a message
+ * @brief Encode a attitude_quaternion struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -157,6 +157,20 @@ static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id,
return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
}
+/**
+ * @brief Encode a attitude_quaternion 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 attitude_quaternion C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion)
+{
+ return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
+}
+
/**
* @brief Send a attitude_quaternion message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h
index 030b564c97..5703a59871 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h
@@ -59,7 +59,7 @@ static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t comp
* @brief Pack a auth_key message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param key key
* @return length of the message in bytes (excluding serial stream start sign)
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a auth_key struct into a message
+ * @brief Encode a auth_key struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -101,6 +101,20 @@ static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t co
return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
}
+/**
+ * @brief Encode a auth_key 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 auth_key C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key)
+{
+ return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key);
+}
+
/**
* @brief Send a auth_key message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h
index 83c8159841..c945aebaea 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h
@@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
* @brief Pack a battery_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 was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param accu_id Accupack ID
* @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt)
@@ -153,7 +153,7 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u
}
/**
- * @brief Encode a battery_status struct into a message
+ * @brief Encode a battery_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -165,6 +165,20 @@ static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint
return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->accu_id, battery_status->voltage_cell_1, battery_status->voltage_cell_2, battery_status->voltage_cell_3, battery_status->voltage_cell_4, battery_status->voltage_cell_5, battery_status->voltage_cell_6, battery_status->current_battery, battery_status->battery_remaining);
}
+/**
+ * @brief Encode a battery_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 battery_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
+{
+ return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->accu_id, battery_status->voltage_cell_1, battery_status->voltage_cell_2, battery_status->voltage_cell_3, battery_status->voltage_cell_4, battery_status->voltage_cell_5, battery_status->voltage_cell_6, battery_status->current_battery, battery_status->battery_remaining);
+}
+
/**
* @brief Send a battery_status message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h
index c7195dfcaa..0b6de930d2 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h
@@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_i
* @brief Pack a change_operator_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t sys
}
/**
- * @brief Encode a change_operator_control struct into a message
+ * @brief Encode a change_operator_control struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -121,6 +121,20 @@ static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system
return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey);
}
+/**
+ * @brief Encode a change_operator_control struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param change_operator_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control)
+{
+ return mavlink_msg_change_operator_control_pack_chan(system_id, component_id, chan, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey);
+}
+
/**
* @brief Send a change_operator_control message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h
index 5cf98e77fe..c6f6a28e4b 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t syst
* @brief Pack a change_operator_control_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param gcs_system_id ID of the GCS this message
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t
}
/**
- * @brief Encode a change_operator_control_ack struct into a message
+ * @brief Encode a change_operator_control_ack struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t sy
return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack);
}
+/**
+ * @brief Encode a change_operator_control_ack 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 change_operator_control_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_change_operator_control_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack)
+{
+ return mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, chan, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack);
+}
+
/**
* @brief Send a change_operator_control_ack message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h
index 82c2835de0..dca2fe6819 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c
* @brief Pack a command_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param command Command ID, as defined by MAV_CMD enum.
* @param result See MAV_RESULT enum
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint
}
/**
- * @brief Encode a command_ack struct into a message
+ * @brief Encode a command_ack struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t
return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result);
}
+/**
+ * @brief Encode a command_ack 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 command_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack)
+{
+ return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result);
+}
+
/**
* @brief Send a command_ack message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h
index 5c44c62844..8f705c0dd2 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t
* @brief Pack a command_long message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a command_long struct into a message
+ * @brief Encode a command_long struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -181,6 +181,20 @@ static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_
return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7);
}
+/**
+ * @brief Encode a command_long 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 command_long C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long)
+{
+ return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7);
+}
+
/**
* @brief Send a command_long message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h
index 782ea9f26b..dc0768e128 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t c
* @brief Pack a data_stream message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param stream_id The ID of the requested data stream
* @param message_rate The requested interval between two messages of this type
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint
}
/**
- * @brief Encode a data_stream struct into a message
+ * @brief Encode a data_stream struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t
return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off);
}
+/**
+ * @brief Encode a data_stream 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 data_stream C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream)
+{
+ return mavlink_msg_data_stream_pack_chan(system_id, component_id, chan, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off);
+}
+
/**
* @brief Send a data_stream message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h
index a111619185..9a6ed87eeb 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t compone
* @brief Pack a debug message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param ind index of debug variable
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t co
}
/**
- * @brief Encode a debug struct into a message
+ * @brief Encode a debug struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t compo
return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value);
}
+/**
+ * @brief Encode a debug 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 debug C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_t* debug)
+{
+ return mavlink_msg_debug_pack_chan(system_id, component_id, chan, msg, debug->time_boot_ms, debug->ind, debug->value);
+}
+
/**
* @brief Send a debug message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h
index 5ee4e323ac..6cfc75212e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h
@@ -77,7 +77,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co
* @brief Pack a debug_vect message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param name Name
* @param time_usec Timestamp
@@ -117,7 +117,7 @@ static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8
}
/**
- * @brief Encode a debug_vect struct into a message
+ * @brief Encode a debug_vect struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -129,6 +129,20 @@ static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
}
+/**
+ * @brief Encode a debug_vect 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 debug_vect C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
+{
+ return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
+}
+
/**
* @brief Send a debug_vect message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h
index c026419a20..4f31698d50 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_file_transfer_dir_list_pack(uint8_t system_id
* @brief Pack a file_transfer_dir_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param transfer_uid Unique transfer ID
* @param dir_path Directory path to list
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_file_transfer_dir_list_pack_chan(uint8_t syst
}
/**
- * @brief Encode a file_transfer_dir_list struct into a message
+ * @brief Encode a file_transfer_dir_list struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_file_transfer_dir_list_encode(uint8_t system_
return mavlink_msg_file_transfer_dir_list_pack(system_id, component_id, msg, file_transfer_dir_list->transfer_uid, file_transfer_dir_list->dir_path, file_transfer_dir_list->flags);
}
+/**
+ * @brief Encode a file_transfer_dir_list 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 file_transfer_dir_list C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_file_transfer_dir_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_dir_list_t* file_transfer_dir_list)
+{
+ return mavlink_msg_file_transfer_dir_list_pack_chan(system_id, component_id, chan, msg, file_transfer_dir_list->transfer_uid, file_transfer_dir_list->dir_path, file_transfer_dir_list->flags);
+}
+
/**
* @brief Send a file_transfer_dir_list message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h
index 86d407d66b..fc6247faca 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_file_transfer_res_pack(uint8_t system_id, uin
* @brief Pack a file_transfer_res message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param transfer_uid Unique transfer ID
* @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_file_transfer_res_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a file_transfer_res struct into a message
+ * @brief Encode a file_transfer_res struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_file_transfer_res_encode(uint8_t system_id, u
return mavlink_msg_file_transfer_res_pack(system_id, component_id, msg, file_transfer_res->transfer_uid, file_transfer_res->result);
}
+/**
+ * @brief Encode a file_transfer_res 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 file_transfer_res C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_file_transfer_res_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_res_t* file_transfer_res)
+{
+ return mavlink_msg_file_transfer_res_pack_chan(system_id, component_id, chan, msg, file_transfer_res->transfer_uid, file_transfer_res->result);
+}
+
/**
* @brief Send a file_transfer_res message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h
index 24bf25413f..05be77339b 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h
@@ -77,7 +77,7 @@ static inline uint16_t mavlink_msg_file_transfer_start_pack(uint8_t system_id, u
* @brief Pack a file_transfer_start message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param transfer_uid Unique transfer ID
* @param dest_path Destination path
@@ -117,7 +117,7 @@ static inline uint16_t mavlink_msg_file_transfer_start_pack_chan(uint8_t system_
}
/**
- * @brief Encode a file_transfer_start struct into a message
+ * @brief Encode a file_transfer_start struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -129,6 +129,20 @@ static inline uint16_t mavlink_msg_file_transfer_start_encode(uint8_t system_id,
return mavlink_msg_file_transfer_start_pack(system_id, component_id, msg, file_transfer_start->transfer_uid, file_transfer_start->dest_path, file_transfer_start->direction, file_transfer_start->file_size, file_transfer_start->flags);
}
+/**
+ * @brief Encode a file_transfer_start 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 file_transfer_start C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_file_transfer_start_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_start_t* file_transfer_start)
+{
+ return mavlink_msg_file_transfer_start_pack_chan(system_id, component_id, chan, msg, file_transfer_start->transfer_uid, file_transfer_start->dest_path, file_transfer_start->direction, file_transfer_start->file_size, file_transfer_start->flags);
+}
+
/**
* @brief Send a file_transfer_start message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h
index 11ab97ee47..7ed3d2a636 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h
@@ -12,7 +12,7 @@ typedef struct __mavlink_global_position_int_t
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
- uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
} mavlink_global_position_int_t;
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
@@ -53,7 +53,7 @@ typedef struct __mavlink_global_position_int_t
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
- * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
* @brief Pack a global_position_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as * 1E7
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
- * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -153,7 +153,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_
}
/**
- * @brief Encode a global_position_int struct into a message
+ * @brief Encode a global_position_int struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -165,6 +165,20 @@ static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id,
return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
}
+/**
+ * @brief Encode a global_position_int 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 global_position_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
+{
+ return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
+}
+
/**
* @brief Send a global_position_int message
* @param chan MAVLink channel to send the message
@@ -177,7 +191,7 @@ static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id,
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
- * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -308,7 +322,7 @@ static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_messa
/**
* @brief Get field hdg from global_position_int message
*
- * @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ * @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
{
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h
index 8153628aa8..1a1c97199e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t sys
* @brief Pack a global_position_setpoint_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude Latitude (WGS84), in degrees * 1E7
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_
}
/**
- * @brief Encode a global_position_setpoint_int struct into a message
+ * @brief Encode a global_position_setpoint_int struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t s
return mavlink_msg_global_position_setpoint_int_pack(system_id, component_id, msg, global_position_setpoint_int->coordinate_frame, global_position_setpoint_int->latitude, global_position_setpoint_int->longitude, global_position_setpoint_int->altitude, global_position_setpoint_int->yaw);
}
+/**
+ * @brief Encode a global_position_setpoint_int 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 global_position_setpoint_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_position_setpoint_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_setpoint_int_t* global_position_setpoint_int)
+{
+ return mavlink_msg_global_position_setpoint_int_pack_chan(system_id, component_id, chan, msg, global_position_setpoint_int->coordinate_frame, global_position_setpoint_int->latitude, global_position_setpoint_int->longitude, global_position_setpoint_int->altitude, global_position_setpoint_int->yaw);
+}
+
/**
* @brief Send a global_position_setpoint_int message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h
index b388fa24ad..f7be74c917 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t
* @brief Pack a global_vision_position_estimate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param x Global X position
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uin
}
/**
- * @brief Encode a global_vision_position_estimate struct into a message
+ * @brief Encode a global_vision_position_estimate struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_
return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw);
}
+/**
+ * @brief Encode a global_vision_position_estimate 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 global_vision_position_estimate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate)
+{
+ return mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw);
+}
+
/**
* @brief Send a global_vision_position_estimate message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h
index bd09cb7534..016e9cb0e6 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uin
* @brief Pack a gps_global_origin message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param latitude Latitude (WGS84), in degrees * 1E7
* @param longitude Longitude (WGS84), in degrees * 1E7
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a gps_global_origin struct into a message
+ * @brief Encode a gps_global_origin struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, u
return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude);
}
+/**
+ * @brief Encode a gps_global_origin 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 gps_global_origin C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin)
+{
+ return mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, chan, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude);
+}
+
/**
* @brief Send a gps_global_origin message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h
index 2136b65eef..3054d4fdab 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h
@@ -8,10 +8,10 @@ typedef struct __mavlink_gps_raw_int_t
int32_t lat; ///< Latitude (WGS84), in degrees * 1E7
int32_t lon; ///< Longitude (WGS84), in degrees * 1E7
int32_t alt; ///< Altitude (WGS84), in meters * 1000 (positive for up)
- uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535
- uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
+ uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
+ uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
+ uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255
} mavlink_gps_raw_int_t;
@@ -52,10 +52,10 @@ typedef struct __mavlink_gps_raw_int_t
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (WGS84), in meters * 1000 (positive for up)
- * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
- * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
+ * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
+ * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
+ * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -104,17 +104,17 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
* @brief Pack a gps_raw_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (WGS84), in meters * 1000 (positive for up)
- * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
- * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
+ * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
+ * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
+ * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -161,7 +161,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint
}
/**
- * @brief Encode a gps_raw_int struct into a message
+ * @brief Encode a gps_raw_int struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -173,6 +173,20 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t
return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible);
}
+/**
+ * @brief Encode a gps_raw_int 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 gps_raw_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
+{
+ return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible);
+}
+
/**
* @brief Send a gps_raw_int message
* @param chan MAVLink channel to send the message
@@ -182,10 +196,10 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t
* @param lat Latitude (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (WGS84), in meters * 1000 (positive for up)
- * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
- * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
+ * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
+ * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
+ * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -289,7 +303,7 @@ static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* m
/**
* @brief Get field eph from gps_raw_int message
*
- * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
+ * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
{
@@ -299,7 +313,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t*
/**
* @brief Get field epv from gps_raw_int message
*
- * @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
+ * @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
{
@@ -309,7 +323,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t*
/**
* @brief Get field vel from gps_raw_int message
*
- * @return GPS ground speed (m/s * 100). If unknown, set to: 65535
+ * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg)
{
@@ -319,7 +333,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t*
/**
* @brief Get field cog from gps_raw_int message
*
- * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg)
{
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h
index cd6dde700f..28d6b57d19 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h
@@ -86,7 +86,7 @@ static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t co
* @brief Pack a gps_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 was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8
}
/**
- * @brief Encode a gps_status struct into a message
+ * @brief Encode a gps_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t
return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
}
+/**
+ * @brief Encode a gps_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 gps_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
+{
+ return mavlink_msg_gps_status_pack_chan(system_id, component_id, chan, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
+}
+
/**
* @brief Send a gps_status message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h
index b2f0b65d06..826138fad1 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h
@@ -83,7 +83,7 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com
* @brief Pack a heartbeat message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
@@ -127,7 +127,7 @@ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_
}
/**
- * @brief Encode a heartbeat struct into a message
+ * @brief Encode a heartbeat struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -139,6 +139,20 @@ static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t c
return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
}
+/**
+ * @brief Encode a heartbeat 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 heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
+{
+ return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
+}
+
/**
* @brief Send a heartbeat message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h
index 6e7492ea65..0dcd95ed32 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t c
* @brief Pack a highres_imu message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
@@ -201,7 +201,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint
}
/**
- * @brief Encode a highres_imu struct into a message
+ * @brief Encode a highres_imu struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -213,6 +213,20 @@ static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t
return mavlink_msg_highres_imu_pack(system_id, component_id, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated);
}
+/**
+ * @brief Encode a highres_imu 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 highres_imu C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu)
+{
+ return mavlink_msg_highres_imu_pack_chan(system_id, component_id, chan, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated);
+}
+
/**
* @brief Send a highres_imu message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h
index 3319d3fd2d..aed5108d05 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t
* @brief Pack a hil_controls message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll_ailerons Control output -1 .. 1
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a hil_controls struct into a message
+ * @brief Encode a hil_controls struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -181,6 +181,20 @@ static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_
return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode);
}
+/**
+ * @brief Encode a hil_controls 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 hil_controls C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
+{
+ return mavlink_msg_hil_controls_pack_chan(system_id, component_id, chan, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode);
+}
+
/**
* @brief Send a hil_controls message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h
index 75ab6835dd..36a551872b 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h
@@ -119,7 +119,7 @@ static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t compo
* @brief Pack a hil_gps message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
@@ -185,7 +185,7 @@ static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a hil_gps struct into a message
+ * @brief Encode a hil_gps struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -197,6 +197,20 @@ static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t com
return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible);
}
+/**
+ * @brief Encode a hil_gps 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 hil_gps C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps)
+{
+ return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible);
+}
+
/**
* @brief Send a hil_gps message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h
index 13e13d47cb..acb1392e14 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h
@@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint
* @brief Pack a hil_optical_flow message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (UNIX)
* @param sensor_id Sensor ID
@@ -145,7 +145,7 @@ static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a hil_optical_flow struct into a message
+ * @brief Encode a hil_optical_flow struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -157,6 +157,20 @@ static inline uint16_t mavlink_msg_hil_optical_flow_encode(uint8_t system_id, ui
return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->flow_x, hil_optical_flow->flow_y, hil_optical_flow->flow_comp_m_x, hil_optical_flow->flow_comp_m_y, hil_optical_flow->quality, hil_optical_flow->ground_distance);
}
+/**
+ * @brief Encode a hil_optical_flow 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 hil_optical_flow C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow)
+{
+ return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->flow_x, hil_optical_flow->flow_y, hil_optical_flow->flow_comp_m_x, hil_optical_flow->flow_comp_m_y, hil_optical_flow->quality, hil_optical_flow->ground_distance);
+}
+
/**
* @brief Send a hil_optical_flow message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h
index f2435dde87..a42bde50b2 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h
@@ -124,7 +124,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uin
* @brief Pack a hil_rc_inputs_raw message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param chan1_raw RC channel 1 value, in microseconds
@@ -193,7 +193,7 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a hil_rc_inputs_raw struct into a message
+ * @brief Encode a hil_rc_inputs_raw struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -205,6 +205,20 @@ static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, u
return mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi);
}
+/**
+ * @brief Encode a hil_rc_inputs_raw 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 hil_rc_inputs_raw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw)
+{
+ return mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, chan, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi);
+}
+
/**
* @brief Send a hil_rc_inputs_raw message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h
index 422e55adc8..6c2667473d 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t co
* @brief Pack a hil_sensor message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
@@ -201,7 +201,7 @@ static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8
}
/**
- * @brief Encode a hil_sensor struct into a message
+ * @brief Encode a hil_sensor struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -213,6 +213,20 @@ static inline uint16_t mavlink_msg_hil_sensor_encode(uint8_t system_id, uint8_t
return mavlink_msg_hil_sensor_pack(system_id, component_id, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated);
}
+/**
+ * @brief Encode a hil_sensor struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param hil_sensor C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor)
+{
+ return mavlink_msg_hil_sensor_pack_chan(system_id, component_id, chan, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated);
+}
+
/**
* @brief Send a hil_sensor message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h
index 1d3f286649..bcc8577670 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h
@@ -134,7 +134,7 @@ static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t com
* @brief Pack a hil_state message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
@@ -209,7 +209,7 @@ static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_
}
/**
- * @brief Encode a hil_state struct into a message
+ * @brief Encode a hil_state struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -221,6 +221,20 @@ static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t c
return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
}
+/**
+ * @brief Encode a hil_state 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 hil_state C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
+{
+ return mavlink_msg_hil_state_pack_chan(system_id, component_id, chan, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
+}
+
/**
* @brief Send a hil_state message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h
index 0474e64a2b..732176193e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h
@@ -132,7 +132,7 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id,
* @brief Pack a hil_state_quaternion message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param attitude_quaternion Vehicle attitude expressed as normalized quaternion
@@ -205,7 +205,7 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system
}
/**
- * @brief Encode a hil_state_quaternion struct into a message
+ * @brief Encode a hil_state_quaternion struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -217,6 +217,20 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_encode(uint8_t system_id
return mavlink_msg_hil_state_quaternion_pack(system_id, component_id, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc);
}
+/**
+ * @brief Encode a hil_state_quaternion 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 hil_state_quaternion C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion)
+{
+ return mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, chan, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc);
+}
+
/**
* @brief Send a hil_state_quaternion message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h
index 56723f3d7d..a0b72c0e1e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, ui
* @brief Pack a local_position_ned message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_i
}
/**
- * @brief Encode a local_position_ned struct into a message
+ * @brief Encode a local_position_ned struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id,
return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz);
}
+/**
+ * @brief Encode a local_position_ned 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 local_position_ned C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_local_position_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned)
+{
+ return mavlink_msg_local_position_ned_pack_chan(system_id, component_id, chan, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz);
+}
+
/**
* @brief Send a local_position_ned message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h
index c206a2906b..8c46862027 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(
* @brief Pack a local_position_ned_system_global_offset message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_
}
/**
- * @brief Encode a local_position_ned_system_global_offset struct into a message
+ * @brief Encode a local_position_ned_system_global_offset struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encod
return mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw);
}
+/**
+ * @brief Encode a local_position_ned_system_global_offset 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 local_position_ned_system_global_offset C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset)
+{
+ return mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, chan, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw);
+}
+
/**
* @brief Send a local_position_ned_system_global_offset message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h
index 96f35fe625..1794815f8e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i
* @brief Pack a local_position_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
* @param x x position
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t sys
}
/**
- * @brief Encode a local_position_setpoint struct into a message
+ * @brief Encode a local_position_setpoint struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system
return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->coordinate_frame, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw);
}
+/**
+ * @brief Encode a local_position_setpoint 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 local_position_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_local_position_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint)
+{
+ return mavlink_msg_local_position_setpoint_pack_chan(system_id, component_id, chan, msg, local_position_setpoint->coordinate_frame, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw);
+}
+
/**
* @brief Send a local_position_setpoint message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h
index c9e4a4f8a5..6b6e9e148a 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_
* @brief Pack a manual_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target The system to be controlled.
* @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, u
}
/**
- * @brief Encode a manual_control struct into a message
+ * @brief Encode a manual_control struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint
return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons);
}
+/**
+ * @brief Encode a manual_control struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param manual_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_manual_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control)
+{
+ return mavlink_msg_manual_control_pack_chan(system_id, component_id, chan, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons);
+}
+
/**
* @brief Send a manual_control message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h
index d59e212921..a694947c12 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8
* @brief Pack a manual_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a manual_setpoint struct into a message
+ * @brief Encode a manual_setpoint struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uin
return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch);
}
+/**
+ * @brief Encode a manual_setpoint 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 manual_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_manual_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint)
+{
+ return mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, chan, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch);
+}
+
/**
* @brief Send a manual_setpoint message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h
index f8ae21b05c..5f79329c25 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h
@@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t c
* @brief Pack a memory_vect message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param address Starting address of the debug variables
* @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint
}
/**
- * @brief Encode a memory_vect struct into a message
+ * @brief Encode a memory_vect struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -121,6 +121,20 @@ static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t
return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value);
}
+/**
+ * @brief Encode a memory_vect 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 memory_vect C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_memory_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect)
+{
+ return mavlink_msg_memory_vect_pack_chan(system_id, component_id, chan, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value);
+}
+
/**
* @brief Send a memory_vect message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h
index 32825647f9..7421d8394a 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t c
* @brief Pack a mission_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint
}
/**
- * @brief Encode a mission_ack struct into a message
+ * @brief Encode a mission_ack struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t
return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type);
}
+/**
+ * @brief Encode a mission_ack 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 mission_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack)
+{
+ return mavlink_msg_mission_ack_pack_chan(system_id, component_id, chan, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type);
+}
+
/**
* @brief Send a mission_ack message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h
index 06d2ac2e79..8f441c8e5c 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uin
* @brief Pack a mission_clear_all message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a mission_clear_all struct into a message
+ * @brief Encode a mission_clear_all struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, u
return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component);
}
+/**
+ * @brief Encode a mission_clear_all 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 mission_clear_all C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_clear_all_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all)
+{
+ return mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, chan, msg, mission_clear_all->target_system, mission_clear_all->target_component);
+}
+
/**
* @brief Send a mission_clear_all message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h
index b28cec6f6d..eac7793067 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t
* @brief Pack a mission_count message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, ui
}
/**
- * @brief Encode a mission_count struct into a message
+ * @brief Encode a mission_count struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8
return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count);
}
+/**
+ * @brief Encode a mission_count 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 mission_count C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count)
+{
+ return mavlink_msg_mission_count_pack_chan(system_id, component_id, chan, msg, mission_count->target_system, mission_count->target_component, mission_count->count);
+}
+
/**
* @brief Send a mission_count message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h
index 5bf0899bea..dbcdbd3f9c 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h
@@ -59,7 +59,7 @@ static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8
* @brief Pack a mission_current message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a mission_current struct into a message
+ * @brief Encode a mission_current struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -101,6 +101,20 @@ static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uin
return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq);
}
+/**
+ * @brief Encode a mission_current 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 mission_current C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current)
+{
+ return mavlink_msg_mission_current_pack_chan(system_id, component_id, chan, msg, mission_current->seq);
+}
+
/**
* @brief Send a mission_current message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h
index ed9d6e4af7..634f80c379 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h
@@ -124,7 +124,7 @@ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t
* @brief Pack a mission_item message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -193,7 +193,7 @@ static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a mission_item struct into a message
+ * @brief Encode a mission_item struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -205,6 +205,20 @@ static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_
return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z);
}
+/**
+ * @brief Encode a mission_item 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 mission_item C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item)
+{
+ return mavlink_msg_mission_item_pack_chan(system_id, component_id, chan, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z);
+}
+
/**
* @brief Send a mission_item message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h
index 3f8a51a134..f3744fde6c 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h
@@ -59,7 +59,7 @@ static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id,
* @brief Pack a mission_item_reached message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system
}
/**
- * @brief Encode a mission_item_reached struct into a message
+ * @brief Encode a mission_item_reached struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -101,6 +101,20 @@ static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id
return mavlink_msg_mission_item_reached_pack(system_id, component_id, msg, mission_item_reached->seq);
}
+/**
+ * @brief Encode a mission_item_reached 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 mission_item_reached C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_item_reached_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached)
+{
+ return mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, chan, msg, mission_item_reached->seq);
+}
+
/**
* @brief Send a mission_item_reached message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h
index 0ced17614e..ac84e35540 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8
* @brief Pack a mission_request message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a mission_request struct into a message
+ * @brief Encode a mission_request struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uin
return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq);
}
+/**
+ * @brief Encode a mission_request 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 mission_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request)
+{
+ return mavlink_msg_mission_request_pack_chan(system_id, component_id, chan, msg, mission_request->target_system, mission_request->target_component, mission_request->seq);
+}
+
/**
* @brief Send a mission_request message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h
index 391df7f4da..d999babdbd 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id,
* @brief Pack a mission_request_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system
}
/**
- * @brief Encode a mission_request_list struct into a message
+ * @brief Encode a mission_request_list struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id
return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component);
}
+/**
+ * @brief Encode a mission_request_list 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 mission_request_list C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list)
+{
+ return mavlink_msg_mission_request_list_pack_chan(system_id, component_id, chan, msg, mission_request_list->target_system, mission_request_list->target_component);
+}
+
/**
* @brief Send a mission_request_list message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h
index d5a1c69397..35c7e12856 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t sys
* @brief Pack a mission_request_partial_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_
}
/**
- * @brief Encode a mission_request_partial_list struct into a message
+ * @brief Encode a mission_request_partial_list struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t s
return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index);
}
+/**
+ * @brief Encode a mission_request_partial_list 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 mission_request_partial_list C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list)
+{
+ return mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, chan, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index);
+}
+
/**
* @brief Send a mission_request_partial_list message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h
index 2e145aa3e9..63b37cf8c8 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, u
* @brief Pack a mission_set_current message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_
}
/**
- * @brief Encode a mission_set_current struct into a message
+ * @brief Encode a mission_set_current struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id,
return mavlink_msg_mission_set_current_pack(system_id, component_id, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq);
}
+/**
+ * @brief Encode a mission_set_current 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 mission_set_current C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_set_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current)
+{
+ return mavlink_msg_mission_set_current_pack_chan(system_id, component_id, chan, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq);
+}
+
/**
* @brief Send a mission_set_current message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h
index 6342f60383..7de38bd7b5 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t syste
* @brief Pack a mission_write_partial_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t
}
/**
- * @brief Encode a mission_write_partial_list struct into a message
+ * @brief Encode a mission_write_partial_list struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t sys
return mavlink_msg_mission_write_partial_list_pack(system_id, component_id, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index);
}
+/**
+ * @brief Encode a mission_write_partial_list 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 mission_write_partial_list C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_write_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list)
+{
+ return mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, chan, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index);
+}
+
/**
* @brief Send a mission_write_partial_list message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h
index a9d28a3d05..fbf4f75c95 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uin
* @brief Pack a named_value_float message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a named_value_float struct into a message
+ * @brief Encode a named_value_float struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, u
return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value);
}
+/**
+ * @brief Encode a named_value_float 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 named_value_float C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_named_value_float_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float)
+{
+ return mavlink_msg_named_value_float_pack_chan(system_id, component_id, chan, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value);
+}
+
/**
* @brief Send a named_value_float message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h
index ea53ea888d..052f247935 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h
@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8
* @brief Pack a named_value_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
@@ -101,7 +101,7 @@ static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a named_value_int struct into a message
+ * @brief Encode a named_value_int struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -113,6 +113,20 @@ static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uin
return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value);
}
+/**
+ * @brief Encode a named_value_int 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 named_value_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_named_value_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int)
+{
+ return mavlink_msg_named_value_int_pack_chan(system_id, component_id, chan, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value);
+}
+
/**
* @brief Send a named_value_int message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h
index e9fa0f5220..e95c144de7 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h
@@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id,
* @brief Pack a nav_controller_output message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
@@ -145,7 +145,7 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t syste
}
/**
- * @brief Encode a nav_controller_output struct into a message
+ * @brief Encode a nav_controller_output struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -157,6 +157,20 @@ static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_i
return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error);
}
+/**
+ * @brief Encode a nav_controller_output 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 nav_controller_output C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output)
+{
+ return mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, chan, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error);
+}
+
/**
* @brief Send a nav_controller_output message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h
index c0e765a444..4debb6e663 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h
@@ -83,7 +83,7 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_pack(uint8_t system_id,
* @brief Pack a omnidirectional_flow message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
@@ -126,7 +126,7 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_pack_chan(uint8_t system
}
/**
- * @brief Encode a omnidirectional_flow struct into a message
+ * @brief Encode a omnidirectional_flow struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -138,6 +138,20 @@ static inline uint16_t mavlink_msg_omnidirectional_flow_encode(uint8_t system_id
return mavlink_msg_omnidirectional_flow_pack(system_id, component_id, msg, omnidirectional_flow->time_usec, omnidirectional_flow->sensor_id, omnidirectional_flow->left, omnidirectional_flow->right, omnidirectional_flow->quality, omnidirectional_flow->front_distance_m);
}
+/**
+ * @brief Encode a omnidirectional_flow 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 omnidirectional_flow C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_omnidirectional_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_omnidirectional_flow_t* omnidirectional_flow)
+{
+ return mavlink_msg_omnidirectional_flow_pack_chan(system_id, component_id, chan, msg, omnidirectional_flow->time_usec, omnidirectional_flow->sensor_id, omnidirectional_flow->left, omnidirectional_flow->right, omnidirectional_flow->quality, omnidirectional_flow->front_distance_m);
+}
+
/**
* @brief Send a omnidirectional_flow message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h
index e01dc5e79c..cf6db9147e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h
@@ -8,8 +8,8 @@ typedef struct __mavlink_optical_flow_t
float flow_comp_m_x; ///< Flow in meters in x-sensor direction, angular-speed compensated
float flow_comp_m_y; ///< Flow in meters in y-sensor direction, angular-speed compensated
float ground_distance; ///< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
- int16_t flow_x; ///< Flow in pixels in x-sensor direction
- int16_t flow_y; ///< Flow in pixels in y-sensor direction
+ int16_t flow_x; ///< Flow in pixels * 10 in x-sensor direction (dezi-pixels)
+ int16_t flow_y; ///< Flow in pixels * 10 in y-sensor direction (dezi-pixels)
uint8_t sensor_id; ///< Sensor ID
uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality
} mavlink_optical_flow_t;
@@ -45,8 +45,8 @@ typedef struct __mavlink_optical_flow_t
*
* @param time_usec Timestamp (UNIX)
* @param sensor_id Sensor ID
- * @param flow_x Flow in pixels in x-sensor direction
- * @param flow_y Flow in pixels in y-sensor direction
+ * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels)
+ * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels)
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
@@ -94,12 +94,12 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
* @brief Pack a optical_flow message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (UNIX)
* @param sensor_id Sensor ID
- * @param flow_x Flow in pixels in x-sensor direction
- * @param flow_y Flow in pixels in y-sensor direction
+ * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels)
+ * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels)
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
@@ -145,7 +145,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a optical_flow struct into a message
+ * @brief Encode a optical_flow struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -157,14 +157,28 @@ static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_
return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance);
}
+/**
+ * @brief Encode a optical_flow 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 optical_flow C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
+{
+ return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance);
+}
+
/**
* @brief Send a optical_flow message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (UNIX)
* @param sensor_id Sensor ID
- * @param flow_x Flow in pixels in x-sensor direction
- * @param flow_y Flow in pixels in y-sensor direction
+ * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels)
+ * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels)
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
@@ -237,7 +251,7 @@ static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_messa
/**
* @brief Get field flow_x from optical_flow message
*
- * @return Flow in pixels in x-sensor direction
+ * @return Flow in pixels * 10 in x-sensor direction (dezi-pixels)
*/
static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg)
{
@@ -247,7 +261,7 @@ static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_
/**
* @brief Get field flow_y from optical_flow message
*
- * @return Flow in pixels in y-sensor direction
+ * @return Flow in pixels * 10 in y-sensor direction (dezi-pixels)
*/
static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg)
{
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h
index da61181b2c..39e0072741 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, ui
* @brief Pack a param_request_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_i
}
/**
- * @brief Encode a param_request_list struct into a message
+ * @brief Encode a param_request_list struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id,
return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component);
}
+/**
+ * @brief Encode a param_request_list 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 param_request_list C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list)
+{
+ return mavlink_msg_param_request_list_pack_chan(system_id, component_id, chan, msg, param_request_list->target_system, param_request_list->target_component);
+}
+
/**
* @brief Send a param_request_list message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h
index 6b15680260..5d9113114b 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h
@@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, ui
* @brief Pack a param_request_read message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_i
}
/**
- * @brief Encode a param_request_read struct into a message
+ * @brief Encode a param_request_read struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -121,6 +121,20 @@ static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id,
return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index);
}
+/**
+ * @brief Encode a param_request_read 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 param_request_read C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_request_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read)
+{
+ return mavlink_msg_param_request_read_pack_chan(system_id, component_id, chan, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index);
+}
+
/**
* @brief Send a param_request_read message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h
index 66b0f6629b..1bd1f00596 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h
@@ -77,7 +77,7 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com
* @brief Pack a param_set message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -117,7 +117,7 @@ static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_
}
/**
- * @brief Encode a param_set struct into a message
+ * @brief Encode a param_set struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -129,6 +129,20 @@ static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t c
return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type);
}
+/**
+ * @brief Encode a param_set 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 param_set C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
+{
+ return mavlink_msg_param_set_pack_chan(system_id, component_id, chan, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type);
+}
+
/**
* @brief Send a param_set message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h
index 5991393746..17c759811f 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h
@@ -77,7 +77,7 @@ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t c
* @brief Pack a param_value message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
@@ -117,7 +117,7 @@ static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint
}
/**
- * @brief Encode a param_value struct into a message
+ * @brief Encode a param_value struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -129,6 +129,20 @@ static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t
return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
}
+/**
+ * @brief Encode a param_value 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 param_value C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_value_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
+{
+ return mavlink_msg_param_value_pack_chan(system_id, component_id, chan, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
+}
+
/**
* @brief Send a param_value message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h
index 5a4c50907d..0c68ca1765 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen
* @brief Pack a ping message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Unix timestamp in microseconds
* @param seq PING sequence
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t com
}
/**
- * @brief Encode a ping struct into a message
+ * @brief Encode a ping struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t compon
return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component);
}
+/**
+ * @brief Encode a ping 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 ping C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ping_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_t* ping)
+{
+ return mavlink_msg_ping_pack_chan(system_id, component_id, chan, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component);
+}
+
/**
* @brief Send a ping message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h
index 06e6a55425..fceb7d1688 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_radio_status_pack(uint8_t system_id, uint8_t
* @brief Pack a radio_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 was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param rssi local signal strength
* @param remrssi remote signal strength
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_radio_status_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a radio_status struct into a message
+ * @brief Encode a radio_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_radio_status_encode(uint8_t system_id, uint8_
return mavlink_msg_radio_status_pack(system_id, component_id, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed);
}
+/**
+ * @brief Encode a radio_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 radio_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_radio_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status)
+{
+ return mavlink_msg_radio_status_pack_chan(system_id, component_id, chan, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed);
+}
+
/**
* @brief Send a radio_status message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h
index ce88636473..62a9b6eeae 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h
@@ -104,7 +104,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo
* @brief Pack a raw_imu message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (raw)
@@ -161,7 +161,7 @@ static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a raw_imu struct into a message
+ * @brief Encode a raw_imu struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -173,6 +173,20 @@ static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t com
return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag);
}
+/**
+ * @brief Encode a raw_imu 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 raw_imu C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu)
+{
+ return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag);
+}
+
/**
* @brief Send a raw_imu message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h
index dcc2cbe063..82c5fad4ab 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t
* @brief Pack a raw_pressure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (raw)
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a raw_pressure struct into a message
+ * @brief Encode a raw_pressure struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_
return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
}
+/**
+ * @brief Encode a raw_pressure 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 raw_pressure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_raw_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
+{
+ return mavlink_msg_raw_pressure_pack_chan(system_id, component_id, chan, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
+}
+
/**
* @brief Send a raw_pressure message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h
index 9854a190ce..0d8a1514b1 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h
@@ -4,14 +4,14 @@
typedef struct __mavlink_rc_channels_override_t
{
- uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
- uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
- uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
- uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
- uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
- uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
- uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
- uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
+ uint16_t chan1_raw; ///< RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ uint16_t chan2_raw; ///< RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ uint16_t chan3_raw; ///< RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ uint16_t chan4_raw; ///< RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ uint16_t chan5_raw; ///< RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ uint16_t chan6_raw; ///< RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ uint16_t chan7_raw; ///< RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ uint16_t chan8_raw; ///< RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_rc_channels_override_t;
@@ -49,14 +49,14 @@ typedef struct __mavlink_rc_channels_override_t
*
* @param target_system System ID
* @param target_component Component ID
- * @param chan1_raw RC channel 1 value, in microseconds
- * @param chan2_raw RC channel 2 value, in microseconds
- * @param chan3_raw RC channel 3 value, in microseconds
- * @param chan4_raw RC channel 4 value, in microseconds
- * @param chan5_raw RC channel 5 value, in microseconds
- * @param chan6_raw RC channel 6 value, in microseconds
- * @param chan7_raw RC channel 7 value, in microseconds
- * @param chan8_raw RC channel 8 value, in microseconds
+ * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -104,18 +104,18 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id,
* @brief Pack a rc_channels_override message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
- * @param chan1_raw RC channel 1 value, in microseconds
- * @param chan2_raw RC channel 2 value, in microseconds
- * @param chan3_raw RC channel 3 value, in microseconds
- * @param chan4_raw RC channel 4 value, in microseconds
- * @param chan5_raw RC channel 5 value, in microseconds
- * @param chan6_raw RC channel 6 value, in microseconds
- * @param chan7_raw RC channel 7 value, in microseconds
- * @param chan8_raw RC channel 8 value, in microseconds
+ * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -161,7 +161,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system
}
/**
- * @brief Encode a rc_channels_override struct into a message
+ * @brief Encode a rc_channels_override struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -173,20 +173,34 @@ static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id
return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw);
}
+/**
+ * @brief Encode a rc_channels_override struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param rc_channels_override C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rc_channels_override_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override)
+{
+ return mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, chan, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw);
+}
+
/**
* @brief Send a rc_channels_override message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
- * @param chan1_raw RC channel 1 value, in microseconds
- * @param chan2_raw RC channel 2 value, in microseconds
- * @param chan3_raw RC channel 3 value, in microseconds
- * @param chan4_raw RC channel 4 value, in microseconds
- * @param chan5_raw RC channel 5 value, in microseconds
- * @param chan6_raw RC channel 6 value, in microseconds
- * @param chan7_raw RC channel 7 value, in microseconds
- * @param chan8_raw RC channel 8 value, in microseconds
+ * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
+ * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -259,7 +273,7 @@ static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(cons
/**
* @brief Get field chan1_raw from rc_channels_override message
*
- * @return RC channel 1 value, in microseconds
+ * @return RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg)
{
@@ -269,7 +283,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavl
/**
* @brief Get field chan2_raw from rc_channels_override message
*
- * @return RC channel 2 value, in microseconds
+ * @return RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg)
{
@@ -279,7 +293,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavl
/**
* @brief Get field chan3_raw from rc_channels_override message
*
- * @return RC channel 3 value, in microseconds
+ * @return RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg)
{
@@ -289,7 +303,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavl
/**
* @brief Get field chan4_raw from rc_channels_override message
*
- * @return RC channel 4 value, in microseconds
+ * @return RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg)
{
@@ -299,7 +313,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavl
/**
* @brief Get field chan5_raw from rc_channels_override message
*
- * @return RC channel 5 value, in microseconds
+ * @return RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg)
{
@@ -309,7 +323,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavl
/**
* @brief Get field chan6_raw from rc_channels_override message
*
- * @return RC channel 6 value, in microseconds
+ * @return RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg)
{
@@ -319,7 +333,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavl
/**
* @brief Get field chan7_raw from rc_channels_override message
*
- * @return RC channel 7 value, in microseconds
+ * @return RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg)
{
@@ -329,7 +343,7 @@ static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavl
/**
* @brief Get field chan8_raw from rc_channels_override message
*
- * @return RC channel 8 value, in microseconds
+ * @return RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg)
{
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h
index 4c1315bed2..3c0aed0202 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h
@@ -5,14 +5,14 @@
typedef struct __mavlink_rc_channels_raw_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
- uint16_t chan1_raw; ///< RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused.
- uint16_t chan2_raw; ///< RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused.
- uint16_t chan3_raw; ///< RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused.
- uint16_t chan4_raw; ///< RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused.
- uint16_t chan5_raw; ///< RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused.
- uint16_t chan6_raw; ///< RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused.
- uint16_t chan7_raw; ///< RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused.
- uint16_t chan8_raw; ///< RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused.
+ uint16_t chan1_raw; ///< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan2_raw; ///< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan3_raw; ///< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan4_raw; ///< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan5_raw; ///< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan6_raw; ///< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan7_raw; ///< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ uint16_t chan8_raw; ///< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
} mavlink_rc_channels_raw_t;
@@ -51,14 +51,14 @@ typedef struct __mavlink_rc_channels_raw_t
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
- * @param chan1_raw RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan2_raw RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan3_raw RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan4_raw RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan5_raw RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan6_raw RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan7_raw RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan8_raw RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -109,18 +109,18 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8
* @brief Pack a rc_channels_raw message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
- * @param chan1_raw RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan2_raw RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan3_raw RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan4_raw RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan5_raw RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan6_raw RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan7_raw RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan8_raw RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a rc_channels_raw struct into a message
+ * @brief Encode a rc_channels_raw struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -181,20 +181,34 @@ static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uin
return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi);
}
+/**
+ * @brief Encode a rc_channels_raw struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param rc_channels_raw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rc_channels_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw)
+{
+ return mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, chan, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi);
+}
+
/**
* @brief Send a rc_channels_raw message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
- * @param chan1_raw RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan2_raw RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan3_raw RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan4_raw RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan5_raw RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan6_raw RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan7_raw RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused.
- * @param chan8_raw RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
+ * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -270,7 +284,7 @@ static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message
/**
* @brief Get field chan1_raw from rc_channels_raw message
*
- * @return RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg)
{
@@ -280,7 +294,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_m
/**
* @brief Get field chan2_raw from rc_channels_raw message
*
- * @return RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg)
{
@@ -290,7 +304,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_m
/**
* @brief Get field chan3_raw from rc_channels_raw message
*
- * @return RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg)
{
@@ -300,7 +314,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_m
/**
* @brief Get field chan4_raw from rc_channels_raw message
*
- * @return RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg)
{
@@ -310,7 +324,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_m
/**
* @brief Get field chan5_raw from rc_channels_raw message
*
- * @return RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg)
{
@@ -320,7 +334,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_m
/**
* @brief Get field chan6_raw from rc_channels_raw message
*
- * @return RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg)
{
@@ -330,7 +344,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_m
/**
* @brief Get field chan7_raw from rc_channels_raw message
*
- * @return RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg)
{
@@ -340,7 +354,7 @@ static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_m
/**
* @brief Get field chan8_raw from rc_channels_raw message
*
- * @return RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused.
+ * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg)
{
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
index be6322bcd3..2153ab3928 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
@@ -5,14 +5,14 @@
typedef struct __mavlink_rc_channels_scaled_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
- int16_t chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- int16_t chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- int16_t chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- int16_t chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- int16_t chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- int16_t chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- int16_t chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- int16_t chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ int16_t chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ int16_t chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ int16_t chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ int16_t chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ int16_t chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ int16_t chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ int16_t chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ int16_t chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
} mavlink_rc_channels_scaled_t;
@@ -51,14 +51,14 @@ typedef struct __mavlink_rc_channels_scaled_t
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
- * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -109,18 +109,18 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui
* @brief Pack a rc_channels_scaled message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
- * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_i
}
/**
- * @brief Encode a rc_channels_scaled struct into a message
+ * @brief Encode a rc_channels_scaled struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -181,20 +181,34 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id,
return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi);
}
+/**
+ * @brief Encode a rc_channels_scaled struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param rc_channels_scaled C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rc_channels_scaled_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled)
+{
+ return mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, chan, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi);
+}
+
/**
* @brief Send a rc_channels_scaled message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
- * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
- * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
+ * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -270,7 +284,7 @@ static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_mess
/**
* @brief Get field chan1_scaled from rc_channels_scaled message
*
- * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg)
{
@@ -280,7 +294,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavl
/**
* @brief Get field chan2_scaled from rc_channels_scaled message
*
- * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg)
{
@@ -290,7 +304,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavl
/**
* @brief Get field chan3_scaled from rc_channels_scaled message
*
- * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg)
{
@@ -300,7 +314,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavl
/**
* @brief Get field chan4_scaled from rc_channels_scaled message
*
- * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg)
{
@@ -310,7 +324,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavl
/**
* @brief Get field chan5_scaled from rc_channels_scaled message
*
- * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg)
{
@@ -320,7 +334,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavl
/**
* @brief Get field chan6_scaled from rc_channels_scaled message
*
- * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg)
{
@@ -330,7 +344,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavl
/**
* @brief Get field chan7_scaled from rc_channels_scaled message
*
- * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg)
{
@@ -340,7 +354,7 @@ static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavl
/**
* @brief Get field chan8_scaled from rc_channels_scaled message
*
- * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767.
+ * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg)
{
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h
index ee21d1fe07..c754ad8761 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, u
* @brief Pack a request_data_stream message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_
}
/**
- * @brief Encode a request_data_stream struct into a message
+ * @brief Encode a request_data_stream struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id,
return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
}
+/**
+ * @brief Encode a request_data_stream 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 request_data_stream C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_request_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream)
+{
+ return mavlink_msg_request_data_stream_pack_chan(system_id, component_id, chan, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
+}
+
/**
* @brief Send a request_data_stream message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h
index a7e9df94be..ac3ef4fa9f 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(uin
* @brief Pack a roll_pitch_yaw_rates_thrust_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll_rate Desired roll rate in radians per second
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_cha
}
/**
- * @brief Encode a roll_pitch_yaw_rates_thrust_setpoint struct into a message
+ * @brief Encode a roll_pitch_yaw_rates_thrust_setpoint struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode(u
return mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms, roll_pitch_yaw_rates_thrust_setpoint->roll_rate, roll_pitch_yaw_rates_thrust_setpoint->pitch_rate, roll_pitch_yaw_rates_thrust_setpoint->yaw_rate, roll_pitch_yaw_rates_thrust_setpoint->thrust);
}
+/**
+ * @brief Encode a roll_pitch_yaw_rates_thrust_setpoint 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 roll_pitch_yaw_rates_thrust_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_rates_thrust_setpoint_t* roll_pitch_yaw_rates_thrust_setpoint)
+{
+ return mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_chan(system_id, component_id, chan, msg, roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms, roll_pitch_yaw_rates_thrust_setpoint->roll_rate, roll_pitch_yaw_rates_thrust_setpoint->pitch_rate, roll_pitch_yaw_rates_thrust_setpoint->yaw_rate, roll_pitch_yaw_rates_thrust_setpoint->thrust);
+}
+
/**
* @brief Send a roll_pitch_yaw_rates_thrust_setpoint message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
index 517797655c..626477322b 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uin
* @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll_speed Desired roll angular speed in rad/s
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_cha
}
/**
- * @brief Encode a roll_pitch_yaw_speed_thrust_setpoint struct into a message
+ * @brief Encode a roll_pitch_yaw_speed_thrust_setpoint struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(u
return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust);
}
+/**
+ * @brief Encode a roll_pitch_yaw_speed_thrust_setpoint 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 roll_pitch_yaw_speed_thrust_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
+{
+ return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(system_id, component_id, chan, msg, roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust);
+}
+
/**
* @brief Send a roll_pitch_yaw_speed_thrust_setpoint message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
index aee036022b..ffcdc547b4 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t s
* @brief Pack a roll_pitch_yaw_thrust_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll angle in radians
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint
}
/**
- * @brief Encode a roll_pitch_yaw_thrust_setpoint struct into a message
+ * @brief Encode a roll_pitch_yaw_thrust_setpoint struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(uint8_t
return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_thrust_setpoint->time_boot_ms, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust);
}
+/**
+ * @brief Encode a roll_pitch_yaw_thrust_setpoint 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 roll_pitch_yaw_thrust_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
+{
+ return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(system_id, component_id, chan, msg, roll_pitch_yaw_thrust_setpoint->time_boot_ms, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust);
+}
+
/**
* @brief Send a roll_pitch_yaw_thrust_setpoint message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
index 100fabf16e..fcd54cbb78 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, u
* @brief Pack a safety_allowed_area message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_
}
/**
- * @brief Encode a safety_allowed_area struct into a message
+ * @brief Encode a safety_allowed_area struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id,
return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z);
}
+/**
+ * @brief Encode a safety_allowed_area 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 safety_allowed_area C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_safety_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area)
+{
+ return mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z);
+}
+
/**
* @brief Send a safety_allowed_area message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h
index d365b7aedc..61f6af1554 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h
@@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_i
* @brief Pack a safety_set_allowed_area message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -153,7 +153,7 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t sys
}
/**
- * @brief Encode a safety_set_allowed_area struct into a message
+ * @brief Encode a safety_set_allowed_area struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -165,6 +165,20 @@ static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system
return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z);
}
+/**
+ * @brief Encode a safety_set_allowed_area 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 safety_set_allowed_area C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_safety_set_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
+{
+ return mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z);
+}
+
/**
* @brief Send a safety_set_allowed_area message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h
index 2751ddfe7a..3010d051af 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h
@@ -104,7 +104,7 @@ static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t co
* @brief Pack a scaled_imu message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param xacc X acceleration (mg)
@@ -161,7 +161,7 @@ static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8
}
/**
- * @brief Encode a scaled_imu struct into a message
+ * @brief Encode a scaled_imu struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -173,6 +173,20 @@ static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t
return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag);
}
+/**
+ * @brief Encode a scaled_imu 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 scaled_imu C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_scaled_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu)
+{
+ return mavlink_msg_scaled_imu_pack_chan(system_id, component_id, chan, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag);
+}
+
/**
* @brief Send a scaled_imu message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h
index f54e281958..10324bc941 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8
* @brief Pack a scaled_pressure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a scaled_pressure struct into a message
+ * @brief Encode a scaled_pressure struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uin
return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature);
}
+/**
+ * @brief Encode a scaled_pressure 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 scaled_pressure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_scaled_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure)
+{
+ return mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, chan, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature);
+}
+
/**
* @brief Send a scaled_pressure message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h
index 10bdcbc8c2..6a14e93ed3 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h
@@ -104,7 +104,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint
* @brief Pack a servo_output_raw message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
@@ -161,7 +161,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a servo_output_raw struct into a message
+ * @brief Encode a servo_output_raw struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -173,6 +173,20 @@ static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, ui
return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw);
}
+/**
+ * @brief Encode a servo_output_raw 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 servo_output_raw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_servo_output_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw)
+{
+ return mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, chan, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw);
+}
+
/**
* @brief Send a servo_output_raw message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h
index 0364b42415..6f0d7a69da 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack(uint8_t
* @brief Pack a set_global_position_setpoint_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude Latitude (WGS84), in degrees * 1E7
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack_chan(ui
}
/**
- * @brief Encode a set_global_position_setpoint_int struct into a message
+ * @brief Encode a set_global_position_setpoint_int struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_set_global_position_setpoint_int_encode(uint8
return mavlink_msg_set_global_position_setpoint_int_pack(system_id, component_id, msg, set_global_position_setpoint_int->coordinate_frame, set_global_position_setpoint_int->latitude, set_global_position_setpoint_int->longitude, set_global_position_setpoint_int->altitude, set_global_position_setpoint_int->yaw);
}
+/**
+ * @brief Encode a set_global_position_setpoint_int 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 set_global_position_setpoint_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_global_position_setpoint_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int)
+{
+ return mavlink_msg_set_global_position_setpoint_int_pack_chan(system_id, component_id, chan, msg, set_global_position_setpoint_int->coordinate_frame, set_global_position_setpoint_int->latitude, set_global_position_setpoint_int->longitude, set_global_position_setpoint_int->altitude, set_global_position_setpoint_int->yaw);
+}
+
/**
* @brief Send a set_global_position_setpoint_int message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h
index e3cd4f4419..c444d8d52c 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id,
* @brief Pack a set_gps_global_origin message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param latitude Latitude (WGS84), in degrees * 1E7
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t syste
}
/**
- * @brief Encode a set_gps_global_origin struct into a message
+ * @brief Encode a set_gps_global_origin struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_i
return mavlink_msg_set_gps_global_origin_pack(system_id, component_id, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude);
}
+/**
+ * @brief Encode a set_gps_global_origin 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 set_gps_global_origin C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin)
+{
+ return mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, chan, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude);
+}
+
/**
* @brief Send a set_gps_global_origin message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h
index b92c0560e9..6f2835e031 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_set_local_position_setpoint_pack(uint8_t syst
* @brief Pack a set_local_position_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_set_local_position_setpoint_pack_chan(uint8_t
}
/**
- * @brief Encode a set_local_position_setpoint struct into a message
+ * @brief Encode a set_local_position_setpoint struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_set_local_position_setpoint_encode(uint8_t sy
return mavlink_msg_set_local_position_setpoint_pack(system_id, component_id, msg, set_local_position_setpoint->target_system, set_local_position_setpoint->target_component, set_local_position_setpoint->coordinate_frame, set_local_position_setpoint->x, set_local_position_setpoint->y, set_local_position_setpoint->z, set_local_position_setpoint->yaw);
}
+/**
+ * @brief Encode a set_local_position_setpoint 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 set_local_position_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_local_position_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_local_position_setpoint_t* set_local_position_setpoint)
+{
+ return mavlink_msg_set_local_position_setpoint_pack_chan(system_id, component_id, chan, msg, set_local_position_setpoint->target_system, set_local_position_setpoint->target_component, set_local_position_setpoint->coordinate_frame, set_local_position_setpoint->x, set_local_position_setpoint->y, set_local_position_setpoint->z, set_local_position_setpoint->yaw);
+}
+
/**
* @brief Send a set_local_position_setpoint message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h
index 08ec733098..1aff42cce3 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t comp
* @brief Pack a set_mode message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system The system setting the mode
* @param base_mode The new base mode
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a set_mode struct into a message
+ * @brief Encode a set_mode struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t co
return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode);
}
+/**
+ * @brief Encode a set_mode 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 set_mode C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_mode_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
+{
+ return mavlink_msg_set_mode_pack_chan(system_id, component_id, chan, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode);
+}
+
/**
* @brief Send a set_mode message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h
index b79114e1a5..8ceb8888fc 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack(uint8_t system_
* @brief Pack a set_quad_motors_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID of the system that should set these motor commands
* @param motor_front_nw Front motor in + configuration, front left motor in x configuration
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack_chan(uint8_t sy
}
/**
- * @brief Encode a set_quad_motors_setpoint struct into a message
+ * @brief Encode a set_quad_motors_setpoint struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_set_quad_motors_setpoint_encode(uint8_t syste
return mavlink_msg_set_quad_motors_setpoint_pack(system_id, component_id, msg, set_quad_motors_setpoint->target_system, set_quad_motors_setpoint->motor_front_nw, set_quad_motors_setpoint->motor_right_ne, set_quad_motors_setpoint->motor_back_se, set_quad_motors_setpoint->motor_left_sw);
}
+/**
+ * @brief Encode a set_quad_motors_setpoint 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 set_quad_motors_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_quad_motors_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_quad_motors_setpoint_t* set_quad_motors_setpoint)
+{
+ return mavlink_msg_set_quad_motors_setpoint_pack_chan(system_id, component_id, chan, msg, set_quad_motors_setpoint->target_system, set_quad_motors_setpoint->motor_front_nw, set_quad_motors_setpoint->motor_right_ne, set_quad_motors_setpoint->motor_back_se, set_quad_motors_setpoint->motor_left_sw);
+}
+
/**
* @brief Send a set_quad_motors_setpoint message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h
index 06223845f4..9ef294cc97 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h
@@ -4,10 +4,10 @@
typedef struct __mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t
{
- int16_t roll[4]; ///< Desired roll angle in radians +-PI (+-32767)
- int16_t pitch[4]; ///< Desired pitch angle in radians +-PI (+-32767)
- int16_t yaw[4]; ///< Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
- uint16_t thrust[4]; ///< Collective thrust, scaled to uint16 (0..65535)
+ int16_t roll[4]; ///< Desired roll angle in radians +-PI (+-INT16_MAX)
+ int16_t pitch[4]; ///< Desired pitch angle in radians +-PI (+-INT16_MAX)
+ int16_t yaw[4]; ///< Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)
+ uint16_t thrust[4]; ///< Collective thrust, scaled to uint16 (0..UINT16_MAX)
uint8_t group; ///< ID of the quadrotor group (0 - 255, up to 256 groups supported)
uint8_t mode; ///< ID of the flight mode (0 - 255, up to 256 modes supported)
uint8_t led_red[4]; ///< RGB red channel (0-255)
@@ -56,10 +56,10 @@ typedef struct __mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t
* @param led_red RGB red channel (0-255)
* @param led_blue RGB green channel (0-255)
* @param led_green RGB blue channel (0-255)
- * @param roll Desired roll angle in radians +-PI (+-32767)
- * @param pitch Desired pitch angle in radians +-PI (+-32767)
- * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
- * @param thrust Collective thrust, scaled to uint16 (0..65535)
+ * @param roll Desired roll angle in radians +-PI (+-INT16_MAX)
+ * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX)
+ * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)
+ * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -103,17 +103,17 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack
* @brief Pack a set_quad_swarm_led_roll_pitch_yaw_thrust message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param group ID of the quadrotor group (0 - 255, up to 256 groups supported)
* @param mode ID of the flight mode (0 - 255, up to 256 modes supported)
* @param led_red RGB red channel (0-255)
* @param led_blue RGB green channel (0-255)
* @param led_green RGB blue channel (0-255)
- * @param roll Desired roll angle in radians +-PI (+-32767)
- * @param pitch Desired pitch angle in radians +-PI (+-32767)
- * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
- * @param thrust Collective thrust, scaled to uint16 (0..65535)
+ * @param roll Desired roll angle in radians +-PI (+-INT16_MAX)
+ * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX)
+ * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)
+ * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -155,7 +155,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack
}
/**
- * @brief Encode a set_quad_swarm_led_roll_pitch_yaw_thrust struct into a message
+ * @brief Encode a set_quad_swarm_led_roll_pitch_yaw_thrust struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -167,6 +167,20 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_enco
return mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_quad_swarm_led_roll_pitch_yaw_thrust->group, set_quad_swarm_led_roll_pitch_yaw_thrust->mode, set_quad_swarm_led_roll_pitch_yaw_thrust->led_red, set_quad_swarm_led_roll_pitch_yaw_thrust->led_blue, set_quad_swarm_led_roll_pitch_yaw_thrust->led_green, set_quad_swarm_led_roll_pitch_yaw_thrust->roll, set_quad_swarm_led_roll_pitch_yaw_thrust->pitch, set_quad_swarm_led_roll_pitch_yaw_thrust->yaw, set_quad_swarm_led_roll_pitch_yaw_thrust->thrust);
}
+/**
+ * @brief Encode a set_quad_swarm_led_roll_pitch_yaw_thrust 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 set_quad_swarm_led_roll_pitch_yaw_thrust C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t* set_quad_swarm_led_roll_pitch_yaw_thrust)
+{
+ return mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, chan, msg, set_quad_swarm_led_roll_pitch_yaw_thrust->group, set_quad_swarm_led_roll_pitch_yaw_thrust->mode, set_quad_swarm_led_roll_pitch_yaw_thrust->led_red, set_quad_swarm_led_roll_pitch_yaw_thrust->led_blue, set_quad_swarm_led_roll_pitch_yaw_thrust->led_green, set_quad_swarm_led_roll_pitch_yaw_thrust->roll, set_quad_swarm_led_roll_pitch_yaw_thrust->pitch, set_quad_swarm_led_roll_pitch_yaw_thrust->yaw, set_quad_swarm_led_roll_pitch_yaw_thrust->thrust);
+}
+
/**
* @brief Send a set_quad_swarm_led_roll_pitch_yaw_thrust message
* @param chan MAVLink channel to send the message
@@ -176,10 +190,10 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_enco
* @param led_red RGB red channel (0-255)
* @param led_blue RGB green channel (0-255)
* @param led_green RGB blue channel (0-255)
- * @param roll Desired roll angle in radians +-PI (+-32767)
- * @param pitch Desired pitch angle in radians +-PI (+-32767)
- * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
- * @param thrust Collective thrust, scaled to uint16 (0..65535)
+ * @param roll Desired roll angle in radians +-PI (+-INT16_MAX)
+ * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX)
+ * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)
+ * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -278,7 +292,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_
/**
* @brief Get field roll from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
- * @return Desired roll angle in radians +-PI (+-32767)
+ * @return Desired roll angle in radians +-PI (+-INT16_MAX)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg, int16_t *roll)
{
@@ -288,7 +302,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_
/**
* @brief Get field pitch from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
- * @return Desired pitch angle in radians +-PI (+-32767)
+ * @return Desired pitch angle in radians +-PI (+-INT16_MAX)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg, int16_t *pitch)
{
@@ -298,7 +312,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_
/**
* @brief Get field yaw from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
- * @return Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
+ * @return Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg, int16_t *yaw)
{
@@ -308,7 +322,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_
/**
* @brief Get field thrust from set_quad_swarm_led_roll_pitch_yaw_thrust message
*
- * @return Collective thrust, scaled to uint16 (0..65535)
+ * @return Collective thrust, scaled to uint16 (0..UINT16_MAX)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg, uint16_t *thrust)
{
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h
index 6c62b35305..7d8d526f8b 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h
@@ -4,10 +4,10 @@
typedef struct __mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t
{
- int16_t roll[4]; ///< Desired roll angle in radians +-PI (+-32767)
- int16_t pitch[4]; ///< Desired pitch angle in radians +-PI (+-32767)
- int16_t yaw[4]; ///< Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
- uint16_t thrust[4]; ///< Collective thrust, scaled to uint16 (0..65535)
+ int16_t roll[4]; ///< Desired roll angle in radians +-PI (+-INT16_MAX)
+ int16_t pitch[4]; ///< Desired pitch angle in radians +-PI (+-INT16_MAX)
+ int16_t yaw[4]; ///< Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)
+ uint16_t thrust[4]; ///< Collective thrust, scaled to uint16 (0..UINT16_MAX)
uint8_t group; ///< ID of the quadrotor group (0 - 255, up to 256 groups supported)
uint8_t mode; ///< ID of the flight mode (0 - 255, up to 256 modes supported)
} mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t;
@@ -44,10 +44,10 @@ typedef struct __mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t
*
* @param group ID of the quadrotor group (0 - 255, up to 256 groups supported)
* @param mode ID of the flight mode (0 - 255, up to 256 modes supported)
- * @param roll Desired roll angle in radians +-PI (+-32767)
- * @param pitch Desired pitch angle in radians +-PI (+-32767)
- * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
- * @param thrust Collective thrust, scaled to uint16 (0..65535)
+ * @param roll Desired roll angle in radians +-PI (+-INT16_MAX)
+ * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX)
+ * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)
+ * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -85,14 +85,14 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(uin
* @brief Pack a set_quad_swarm_roll_pitch_yaw_thrust message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param group ID of the quadrotor group (0 - 255, up to 256 groups supported)
* @param mode ID of the flight mode (0 - 255, up to 256 modes supported)
- * @param roll Desired roll angle in radians +-PI (+-32767)
- * @param pitch Desired pitch angle in radians +-PI (+-32767)
- * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
- * @param thrust Collective thrust, scaled to uint16 (0..65535)
+ * @param roll Desired roll angle in radians +-PI (+-INT16_MAX)
+ * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX)
+ * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)
+ * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -128,7 +128,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_cha
}
/**
- * @brief Encode a set_quad_swarm_roll_pitch_yaw_thrust struct into a message
+ * @brief Encode a set_quad_swarm_roll_pitch_yaw_thrust struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -140,16 +140,30 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(u
return mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_quad_swarm_roll_pitch_yaw_thrust->group, set_quad_swarm_roll_pitch_yaw_thrust->mode, set_quad_swarm_roll_pitch_yaw_thrust->roll, set_quad_swarm_roll_pitch_yaw_thrust->pitch, set_quad_swarm_roll_pitch_yaw_thrust->yaw, set_quad_swarm_roll_pitch_yaw_thrust->thrust);
}
+/**
+ * @brief Encode a set_quad_swarm_roll_pitch_yaw_thrust 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 set_quad_swarm_roll_pitch_yaw_thrust C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t* set_quad_swarm_roll_pitch_yaw_thrust)
+{
+ return mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, chan, msg, set_quad_swarm_roll_pitch_yaw_thrust->group, set_quad_swarm_roll_pitch_yaw_thrust->mode, set_quad_swarm_roll_pitch_yaw_thrust->roll, set_quad_swarm_roll_pitch_yaw_thrust->pitch, set_quad_swarm_roll_pitch_yaw_thrust->yaw, set_quad_swarm_roll_pitch_yaw_thrust->thrust);
+}
+
/**
* @brief Send a set_quad_swarm_roll_pitch_yaw_thrust message
* @param chan MAVLink channel to send the message
*
* @param group ID of the quadrotor group (0 - 255, up to 256 groups supported)
* @param mode ID of the flight mode (0 - 255, up to 256 modes supported)
- * @param roll Desired roll angle in radians +-PI (+-32767)
- * @param pitch Desired pitch angle in radians +-PI (+-32767)
- * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
- * @param thrust Collective thrust, scaled to uint16 (0..65535)
+ * @param roll Desired roll angle in radians +-PI (+-INT16_MAX)
+ * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX)
+ * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)
+ * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -212,7 +226,7 @@ static inline uint8_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_mode(
/**
* @brief Get field roll from set_quad_swarm_roll_pitch_yaw_thrust message
*
- * @return Desired roll angle in radians +-PI (+-32767)
+ * @return Desired roll angle in radians +-PI (+-INT16_MAX)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg, int16_t *roll)
{
@@ -222,7 +236,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_roll
/**
* @brief Get field pitch from set_quad_swarm_roll_pitch_yaw_thrust message
*
- * @return Desired pitch angle in radians +-PI (+-32767)
+ * @return Desired pitch angle in radians +-PI (+-INT16_MAX)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg, int16_t *pitch)
{
@@ -232,7 +246,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_pitc
/**
* @brief Get field yaw from set_quad_swarm_roll_pitch_yaw_thrust message
*
- * @return Desired yaw angle in radians, scaled to int16 +-PI (+-32767)
+ * @return Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg, int16_t *yaw)
{
@@ -242,7 +256,7 @@ static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_yaw(
/**
* @brief Get field thrust from set_quad_swarm_roll_pitch_yaw_thrust message
*
- * @return Collective thrust, scaled to uint16 (0..65535)
+ * @return Collective thrust, scaled to uint16 (0..UINT16_MAX)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg, uint16_t *thrust)
{
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
index c379a75d9b..5846ba41f7 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t
* @brief Pack a set_roll_pitch_yaw_speed_thrust message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(uin
}
/**
- * @brief Encode a set_roll_pitch_yaw_speed_thrust struct into a message
+ * @brief Encode a set_roll_pitch_yaw_speed_thrust struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(uint8_
return mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_speed_thrust->target_system, set_roll_pitch_yaw_speed_thrust->target_component, set_roll_pitch_yaw_speed_thrust->roll_speed, set_roll_pitch_yaw_speed_thrust->pitch_speed, set_roll_pitch_yaw_speed_thrust->yaw_speed, set_roll_pitch_yaw_speed_thrust->thrust);
}
+/**
+ * @brief Encode a set_roll_pitch_yaw_speed_thrust 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 set_roll_pitch_yaw_speed_thrust C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust)
+{
+ return mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(system_id, component_id, chan, msg, set_roll_pitch_yaw_speed_thrust->target_system, set_roll_pitch_yaw_speed_thrust->target_component, set_roll_pitch_yaw_speed_thrust->roll_speed, set_roll_pitch_yaw_speed_thrust->pitch_speed, set_roll_pitch_yaw_speed_thrust->yaw_speed, set_roll_pitch_yaw_speed_thrust->thrust);
+}
+
/**
* @brief Send a set_roll_pitch_yaw_speed_thrust message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
index 146891eafb..334fd39e36 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system
* @brief Pack a set_roll_pitch_yaw_thrust message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(uint8_t s
}
/**
- * @brief Encode a set_roll_pitch_yaw_thrust struct into a message
+ * @brief Encode a set_roll_pitch_yaw_thrust struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode(uint8_t syst
return mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust);
}
+/**
+ * @brief Encode a set_roll_pitch_yaw_thrust 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 set_roll_pitch_yaw_thrust C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust)
+{
+ return mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, chan, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust);
+}
+
/**
* @brief Send a set_roll_pitch_yaw_thrust message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h
index f352617a26..93ce345b65 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack(uint8_t system_id, uint8_t
* @brief Pack a setpoint_6dof message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param trans_x Translational Component in x
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack_chan(uint8_t system_id, ui
}
/**
- * @brief Encode a setpoint_6dof struct into a message
+ * @brief Encode a setpoint_6dof struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_setpoint_6dof_encode(uint8_t system_id, uint8
return mavlink_msg_setpoint_6dof_pack(system_id, component_id, msg, setpoint_6dof->target_system, setpoint_6dof->trans_x, setpoint_6dof->trans_y, setpoint_6dof->trans_z, setpoint_6dof->rot_x, setpoint_6dof->rot_y, setpoint_6dof->rot_z);
}
+/**
+ * @brief Encode a setpoint_6dof 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 setpoint_6dof C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_setpoint_6dof_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_setpoint_6dof_t* setpoint_6dof)
+{
+ return mavlink_msg_setpoint_6dof_pack_chan(system_id, component_id, chan, msg, setpoint_6dof->target_system, setpoint_6dof->trans_x, setpoint_6dof->trans_y, setpoint_6dof->trans_z, setpoint_6dof->rot_x, setpoint_6dof->rot_y, setpoint_6dof->rot_z);
+}
+
/**
* @brief Send a setpoint_6dof message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h
index d7622b6965..de80e46459 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h
@@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_setpoint_8dof_pack(uint8_t system_id, uint8_t
* @brief Pack a setpoint_8dof message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param val1 Value 1
@@ -153,7 +153,7 @@ static inline uint16_t mavlink_msg_setpoint_8dof_pack_chan(uint8_t system_id, ui
}
/**
- * @brief Encode a setpoint_8dof struct into a message
+ * @brief Encode a setpoint_8dof struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -165,6 +165,20 @@ static inline uint16_t mavlink_msg_setpoint_8dof_encode(uint8_t system_id, uint8
return mavlink_msg_setpoint_8dof_pack(system_id, component_id, msg, setpoint_8dof->target_system, setpoint_8dof->val1, setpoint_8dof->val2, setpoint_8dof->val3, setpoint_8dof->val4, setpoint_8dof->val5, setpoint_8dof->val6, setpoint_8dof->val7, setpoint_8dof->val8);
}
+/**
+ * @brief Encode a setpoint_8dof 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 setpoint_8dof C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_setpoint_8dof_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_setpoint_8dof_t* setpoint_8dof)
+{
+ return mavlink_msg_setpoint_8dof_pack_chan(system_id, component_id, chan, msg, setpoint_8dof->target_system, setpoint_8dof->val1, setpoint_8dof->val2, setpoint_8dof->val3, setpoint_8dof->val4, setpoint_8dof->val5, setpoint_8dof->val6, setpoint_8dof->val7, setpoint_8dof->val8);
+}
+
/**
* @brief Send a setpoint_8dof message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h
index 6fd32abd25..ebd657cf38 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h
@@ -159,7 +159,7 @@ static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t com
* @brief Pack a sim_state message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param q1 True attitude quaternion component 1
* @param q2 True attitude quaternion component 2
@@ -249,7 +249,7 @@ static inline uint16_t mavlink_msg_sim_state_pack_chan(uint8_t system_id, uint8_
}
/**
- * @brief Encode a sim_state struct into a message
+ * @brief Encode a sim_state struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -261,6 +261,20 @@ static inline uint16_t mavlink_msg_sim_state_encode(uint8_t system_id, uint8_t c
return mavlink_msg_sim_state_pack(system_id, component_id, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd);
}
+/**
+ * @brief Encode a sim_state 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 sim_state C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state)
+{
+ return mavlink_msg_sim_state_pack_chan(system_id, component_id, chan, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd);
+}
+
/**
* @brief Send a sim_state message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h
index 8a002fc113..2db627b96a 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h
@@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint
* @brief Pack a state_correction message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param xErr x position error
* @param yErr y position error
@@ -153,7 +153,7 @@ static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a state_correction struct into a message
+ * @brief Encode a state_correction struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -165,6 +165,20 @@ static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, ui
return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr);
}
+/**
+ * @brief Encode a state_correction 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 state_correction C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_state_correction_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction)
+{
+ return mavlink_msg_state_correction_pack_chan(system_id, component_id, chan, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr);
+}
+
/**
* @brief Send a state_correction message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
index 103486863c..536ca06349 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
@@ -62,7 +62,7 @@ static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t co
* @brief Pack a statustext message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
* @param text Status text message, without null termination character
@@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8
}
/**
- * @brief Encode a statustext struct into a message
+ * @brief Encode a statustext struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -105,6 +105,20 @@ static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t
return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text);
}
+/**
+ * @brief Encode a statustext 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 statustext C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_statustext_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_statustext_t* statustext)
+{
+ return mavlink_msg_statustext_pack_chan(system_id, component_id, chan, msg, statustext->severity, statustext->text);
+}
+
/**
* @brief Send a statustext message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h
index 916bc4f07b..058c630ddd 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h
@@ -119,7 +119,7 @@ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t co
* @brief Pack a sys_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 was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
* @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
@@ -185,7 +185,7 @@ static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8
}
/**
- * @brief Encode a sys_status struct into a message
+ * @brief Encode a sys_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -197,6 +197,20 @@ static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t
return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4);
}
+/**
+ * @brief Encode a sys_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 sys_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status)
+{
+ return mavlink_msg_sys_status_pack_chan(system_id, component_id, chan, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4);
+}
+
/**
* @brief Send a sys_status message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h
index b235fe2056..1807567aea 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t c
* @brief Pack a system_time message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch.
* @param time_boot_ms Timestamp of the component clock since boot time in milliseconds.
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint
}
/**
- * @brief Encode a system_time struct into a message
+ * @brief Encode a system_time struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t
return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms);
}
+/**
+ * @brief Encode a system_time 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 system_time C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_system_time_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_time_t* system_time)
+{
+ return mavlink_msg_system_time_pack_chan(system_id, component_id, chan, msg, system_time->time_unix_usec, system_time->time_boot_ms);
+}
+
/**
* @brief Send a system_time message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h
index 9d459921fe..5b1093a3d7 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t compo
* @brief Pack a vfr_hud message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param airspeed Current airspeed in m/s
* @param groundspeed Current ground speed in m/s
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a vfr_hud struct into a message
+ * @brief Encode a vfr_hud struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t com
return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb);
}
+/**
+ * @brief Encode a vfr_hud 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 vfr_hud C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vfr_hud_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud)
+{
+ return mavlink_msg_vfr_hud_pack_chan(system_id, component_id, chan, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb);
+}
+
/**
* @brief Send a vfr_hud message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h
index 75e4b5b7ab..a254202e4e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_i
* @brief Pack a vicon_position_estimate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param x Global X position
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t sys
}
/**
- * @brief Encode a vicon_position_estimate struct into a message
+ * @brief Encode a vicon_position_estimate struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system
return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw);
}
+/**
+ * @brief Encode a vicon_position_estimate 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 vicon_position_estimate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vicon_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate)
+{
+ return mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, chan, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw);
+}
+
/**
* @brief Send a vicon_position_estimate message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h
index 47ccb11ec0..f7a741b09e 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_
* @brief Pack a vision_position_estimate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param x Global X position
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t sy
}
/**
- * @brief Encode a vision_position_estimate struct into a message
+ * @brief Encode a vision_position_estimate struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t syste
return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw);
}
+/**
+ * @brief Encode a vision_position_estimate 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 vision_position_estimate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate)
+{
+ return mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw);
+}
+
/**
* @brief Send a vision_position_estimate message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h
index c38eee62c0..6602251283 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id,
* @brief Pack a vision_speed_estimate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param x Global X speed
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t syste
}
/**
- * @brief Encode a vision_speed_estimate struct into a message
+ * @brief Encode a vision_speed_estimate struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_i
return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z);
}
+/**
+ * @brief Encode a vision_speed_estimate 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 vision_speed_estimate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
+{
+ return mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, chan, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z);
+}
+
/**
* @brief Send a vision_speed_estimate message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/common/version.h b/mavlink/include/mavlink/v1.0/common/version.h
index c91a641de8..3c354f4229 100644
--- a/mavlink/include/mavlink/v1.0/common/version.h
+++ b/mavlink/include/mavlink/v1.0/common/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Thu Jul 4 13:47:40 2013"
+#define MAVLINK_BUILD_DATE "Tue Sep 10 23:50:05 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h b/mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h
index f5576255ed..f590cda800 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h
@@ -77,6 +77,7 @@ enum MAV_CMD
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
@@ -85,7 +86,8 @@ enum MAV_CMD
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
- MAV_CMD_ENUM_END=401, /* | */
+ MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
+ MAV_CMD_ENUM_END=501, /* | */
};
#endif
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h
index bd0be342fa..bc47a547ad 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_airspeeds_pack(uint8_t system_id, uint8_t com
* @brief Pack a airspeeds message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param airspeed_imu Airspeed estimate from IMU, cm/s
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_airspeeds_pack_chan(uint8_t system_id, uint8_
}
/**
- * @brief Encode a airspeeds struct into a message
+ * @brief Encode a airspeeds struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_airspeeds_encode(uint8_t system_id, uint8_t c
return mavlink_msg_airspeeds_pack(system_id, component_id, msg, airspeeds->time_boot_ms, airspeeds->airspeed_imu, airspeeds->airspeed_pitot, airspeeds->airspeed_hot_wire, airspeeds->airspeed_ultrasonic, airspeeds->aoa, airspeeds->aoy);
}
+/**
+ * @brief Encode a airspeeds 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 airspeeds C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airspeeds_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_airspeeds_t* airspeeds)
+{
+ return mavlink_msg_airspeeds_pack_chan(system_id, component_id, chan, msg, airspeeds->time_boot_ms, airspeeds->airspeed_imu, airspeeds->airspeed_pitot, airspeeds->airspeed_hot_wire, airspeeds->airspeed_ultrasonic, airspeeds->aoa, airspeeds->aoy);
+}
+
/**
* @brief Send a airspeeds message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h
index c1ce66875c..e64787cc73 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_altitudes_pack(uint8_t system_id, uint8_t com
* @brief Pack a altitudes message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param alt_gps GPS altitude in meters, expressed as * 1000 (millimeters), above MSL
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_altitudes_pack_chan(uint8_t system_id, uint8_
}
/**
- * @brief Encode a altitudes struct into a message
+ * @brief Encode a altitudes struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_altitudes_encode(uint8_t system_id, uint8_t c
return mavlink_msg_altitudes_pack(system_id, component_id, msg, altitudes->time_boot_ms, altitudes->alt_gps, altitudes->alt_imu, altitudes->alt_barometric, altitudes->alt_optical_flow, altitudes->alt_range_finder, altitudes->alt_extra);
}
+/**
+ * @brief Encode a altitudes 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 altitudes C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_altitudes_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_altitudes_t* altitudes)
+{
+ return mavlink_msg_altitudes_pack_chan(system_id, component_id, chan, msg, altitudes->time_boot_ms, altitudes->alt_gps, altitudes->alt_imu, altitudes->alt_barometric, altitudes->alt_optical_flow, altitudes->alt_range_finder, altitudes->alt_extra);
+}
+
/**
* @brief Send a altitudes message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h
index d72a4dcacb..581bd35dc5 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h
@@ -87,7 +87,7 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack(uint8_t sy
* @brief Pack a flexifunction_buffer_function message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -133,7 +133,7 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack_chan(uint8
}
/**
- * @brief Encode a flexifunction_buffer_function struct into a message
+ * @brief Encode a flexifunction_buffer_function struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -145,6 +145,20 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_encode(uint8_t
return mavlink_msg_flexifunction_buffer_function_pack(system_id, component_id, msg, flexifunction_buffer_function->target_system, flexifunction_buffer_function->target_component, flexifunction_buffer_function->func_index, flexifunction_buffer_function->func_count, flexifunction_buffer_function->data_address, flexifunction_buffer_function->data_size, flexifunction_buffer_function->data);
}
+/**
+ * @brief Encode a flexifunction_buffer_function 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 flexifunction_buffer_function C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_flexifunction_buffer_function_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_buffer_function_t* flexifunction_buffer_function)
+{
+ return mavlink_msg_flexifunction_buffer_function_pack_chan(system_id, component_id, chan, msg, flexifunction_buffer_function->target_system, flexifunction_buffer_function->target_component, flexifunction_buffer_function->func_index, flexifunction_buffer_function->func_count, flexifunction_buffer_function->data_address, flexifunction_buffer_function->data_size, flexifunction_buffer_function->data);
+}
+
/**
* @brief Send a flexifunction_buffer_function message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h
index 58f1786ef9..790afd52b3 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_pack(uint8_
* @brief Pack a flexifunction_buffer_function_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_pack_chan(u
}
/**
- * @brief Encode a flexifunction_buffer_function_ack struct into a message
+ * @brief Encode a flexifunction_buffer_function_ack struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_encode(uint
return mavlink_msg_flexifunction_buffer_function_ack_pack(system_id, component_id, msg, flexifunction_buffer_function_ack->target_system, flexifunction_buffer_function_ack->target_component, flexifunction_buffer_function_ack->func_index, flexifunction_buffer_function_ack->result);
}
+/**
+ * @brief Encode a flexifunction_buffer_function_ack 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 flexifunction_buffer_function_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_buffer_function_ack_t* flexifunction_buffer_function_ack)
+{
+ return mavlink_msg_flexifunction_buffer_function_ack_pack_chan(system_id, component_id, chan, msg, flexifunction_buffer_function_ack->target_system, flexifunction_buffer_function_ack->target_component, flexifunction_buffer_function_ack->func_index, flexifunction_buffer_function_ack->result);
+}
+
/**
* @brief Send a flexifunction_buffer_function_ack message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h
index 2f6668cf95..ce722c8a4d 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h
@@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_flexifunction_command_pack(uint8_t system_id,
* @brief Pack a flexifunction_command message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -105,7 +105,7 @@ static inline uint16_t mavlink_msg_flexifunction_command_pack_chan(uint8_t syste
}
/**
- * @brief Encode a flexifunction_command struct into a message
+ * @brief Encode a flexifunction_command struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -117,6 +117,20 @@ static inline uint16_t mavlink_msg_flexifunction_command_encode(uint8_t system_i
return mavlink_msg_flexifunction_command_pack(system_id, component_id, msg, flexifunction_command->target_system, flexifunction_command->target_component, flexifunction_command->command_type);
}
+/**
+ * @brief Encode a flexifunction_command 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 flexifunction_command C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_flexifunction_command_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_command_t* flexifunction_command)
+{
+ return mavlink_msg_flexifunction_command_pack_chan(system_id, component_id, chan, msg, flexifunction_command->target_system, flexifunction_command->target_component, flexifunction_command->command_type);
+}
+
/**
* @brief Send a flexifunction_command message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h
index 4798febb01..070dc4bf8d 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_flexifunction_command_ack_pack(uint8_t system
* @brief Pack a flexifunction_command_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param command_type Command acknowledged
* @param result result of acknowledge
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_flexifunction_command_ack_pack_chan(uint8_t s
}
/**
- * @brief Encode a flexifunction_command_ack struct into a message
+ * @brief Encode a flexifunction_command_ack struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_flexifunction_command_ack_encode(uint8_t syst
return mavlink_msg_flexifunction_command_ack_pack(system_id, component_id, msg, flexifunction_command_ack->command_type, flexifunction_command_ack->result);
}
+/**
+ * @brief Encode a flexifunction_command_ack 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 flexifunction_command_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_flexifunction_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_command_ack_t* flexifunction_command_ack)
+{
+ return mavlink_msg_flexifunction_command_ack_pack_chan(system_id, component_id, chan, msg, flexifunction_command_ack->command_type, flexifunction_command_ack->result);
+}
+
/**
* @brief Send a flexifunction_command_ack message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h
index 947bfc5911..ef262a6b1d 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h
@@ -82,7 +82,7 @@ static inline uint16_t mavlink_msg_flexifunction_directory_pack(uint8_t system_i
* @brief Pack a flexifunction_directory message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -125,7 +125,7 @@ static inline uint16_t mavlink_msg_flexifunction_directory_pack_chan(uint8_t sys
}
/**
- * @brief Encode a flexifunction_directory struct into a message
+ * @brief Encode a flexifunction_directory struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -137,6 +137,20 @@ static inline uint16_t mavlink_msg_flexifunction_directory_encode(uint8_t system
return mavlink_msg_flexifunction_directory_pack(system_id, component_id, msg, flexifunction_directory->target_system, flexifunction_directory->target_component, flexifunction_directory->directory_type, flexifunction_directory->start_index, flexifunction_directory->count, flexifunction_directory->directory_data);
}
+/**
+ * @brief Encode a flexifunction_directory 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 flexifunction_directory C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_flexifunction_directory_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_directory_t* flexifunction_directory)
+{
+ return mavlink_msg_flexifunction_directory_pack_chan(system_id, component_id, chan, msg, flexifunction_directory->target_system, flexifunction_directory->target_component, flexifunction_directory->directory_type, flexifunction_directory->start_index, flexifunction_directory->count, flexifunction_directory->directory_data);
+}
+
/**
* @brief Send a flexifunction_directory message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h
index 5489dd6b5e..d3a386ce54 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack(uint8_t syst
* @brief Pack a flexifunction_directory_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack_chan(uint8_t
}
/**
- * @brief Encode a flexifunction_directory_ack struct into a message
+ * @brief Encode a flexifunction_directory_ack struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_flexifunction_directory_ack_encode(uint8_t sy
return mavlink_msg_flexifunction_directory_ack_pack(system_id, component_id, msg, flexifunction_directory_ack->target_system, flexifunction_directory_ack->target_component, flexifunction_directory_ack->directory_type, flexifunction_directory_ack->start_index, flexifunction_directory_ack->count, flexifunction_directory_ack->result);
}
+/**
+ * @brief Encode a flexifunction_directory_ack 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 flexifunction_directory_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_flexifunction_directory_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_directory_ack_t* flexifunction_directory_ack)
+{
+ return mavlink_msg_flexifunction_directory_ack_pack_chan(system_id, component_id, chan, msg, flexifunction_directory_ack->target_system, flexifunction_directory_ack->target_component, flexifunction_directory_ack->directory_type, flexifunction_directory_ack->start_index, flexifunction_directory_ack->count, flexifunction_directory_ack->result);
+}
+
/**
* @brief Send a flexifunction_directory_ack message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h
index 9ffc2caa5f..e50f77b080 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_flexifunction_read_req_pack(uint8_t system_id
* @brief Pack a flexifunction_read_req message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_flexifunction_read_req_pack_chan(uint8_t syst
}
/**
- * @brief Encode a flexifunction_read_req struct into a message
+ * @brief Encode a flexifunction_read_req struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_flexifunction_read_req_encode(uint8_t system_
return mavlink_msg_flexifunction_read_req_pack(system_id, component_id, msg, flexifunction_read_req->target_system, flexifunction_read_req->target_component, flexifunction_read_req->read_req_type, flexifunction_read_req->data_index);
}
+/**
+ * @brief Encode a flexifunction_read_req 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 flexifunction_read_req C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_flexifunction_read_req_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_read_req_t* flexifunction_read_req)
+{
+ return mavlink_msg_flexifunction_read_req_pack_chan(system_id, component_id, chan, msg, flexifunction_read_req->target_system, flexifunction_read_req->target_component, flexifunction_read_req->read_req_type, flexifunction_read_req->data_index);
+}
+
/**
* @brief Send a flexifunction_read_req message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h
index fc7d1d2f8e..41afb3811d 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_flexifunction_set_pack(uint8_t system_id, uin
* @brief Pack a flexifunction_set message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_flexifunction_set_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a flexifunction_set struct into a message
+ * @brief Encode a flexifunction_set struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_flexifunction_set_encode(uint8_t system_id, u
return mavlink_msg_flexifunction_set_pack(system_id, component_id, msg, flexifunction_set->target_system, flexifunction_set->target_component);
}
+/**
+ * @brief Encode a flexifunction_set 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 flexifunction_set C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_flexifunction_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_set_t* flexifunction_set)
+{
+ return mavlink_msg_flexifunction_set_pack_chan(system_id, component_id, chan, msg, flexifunction_set->target_system, flexifunction_set->target_component);
+}
+
/**
* @brief Send a flexifunction_set message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h
index df5645e765..d21ab48168 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f13_pack(uint8_t system_id,
* @brief Pack a serial_udb_extra_f13 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_week_no Serial UDB Extra GPS Week Number
* @param sue_lat_origin Serial UDB Extra MP Origin Latitude
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f13_pack_chan(uint8_t system
}
/**
- * @brief Encode a serial_udb_extra_f13 struct into a message
+ * @brief Encode a serial_udb_extra_f13 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f13_encode(uint8_t system_id
return mavlink_msg_serial_udb_extra_f13_pack(system_id, component_id, msg, serial_udb_extra_f13->sue_week_no, serial_udb_extra_f13->sue_lat_origin, serial_udb_extra_f13->sue_lon_origin, serial_udb_extra_f13->sue_alt_origin);
}
+/**
+ * @brief Encode a serial_udb_extra_f13 struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f13 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f13_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f13_t* serial_udb_extra_f13)
+{
+ return mavlink_msg_serial_udb_extra_f13_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f13->sue_week_no, serial_udb_extra_f13->sue_lat_origin, serial_udb_extra_f13->sue_lon_origin, serial_udb_extra_f13->sue_alt_origin);
+}
+
/**
* @brief Send a serial_udb_extra_f13 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h
index 5e38a590a4..6ac12f28a6 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack(uint8_t system_id,
* @brief Pack a serial_udb_extra_f14 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_WIND_ESTIMATION Serial UDB Extra Wind Estimation Enabled
* @param sue_GPS_TYPE Serial UDB Extra Type of GPS Unit
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack_chan(uint8_t system
}
/**
- * @brief Encode a serial_udb_extra_f14 struct into a message
+ * @brief Encode a serial_udb_extra_f14 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -181,6 +181,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f14_encode(uint8_t system_id
return mavlink_msg_serial_udb_extra_f14_pack(system_id, component_id, msg, serial_udb_extra_f14->sue_WIND_ESTIMATION, serial_udb_extra_f14->sue_GPS_TYPE, serial_udb_extra_f14->sue_DR, serial_udb_extra_f14->sue_BOARD_TYPE, serial_udb_extra_f14->sue_AIRFRAME, serial_udb_extra_f14->sue_RCON, serial_udb_extra_f14->sue_TRAP_FLAGS, serial_udb_extra_f14->sue_TRAP_SOURCE, serial_udb_extra_f14->sue_osc_fail_count, serial_udb_extra_f14->sue_CLOCK_CONFIG, serial_udb_extra_f14->sue_FLIGHT_PLAN_TYPE);
}
+/**
+ * @brief Encode a serial_udb_extra_f14 struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f14 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f14_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f14_t* serial_udb_extra_f14)
+{
+ return mavlink_msg_serial_udb_extra_f14_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f14->sue_WIND_ESTIMATION, serial_udb_extra_f14->sue_GPS_TYPE, serial_udb_extra_f14->sue_DR, serial_udb_extra_f14->sue_BOARD_TYPE, serial_udb_extra_f14->sue_AIRFRAME, serial_udb_extra_f14->sue_RCON, serial_udb_extra_f14->sue_TRAP_FLAGS, serial_udb_extra_f14->sue_TRAP_SOURCE, serial_udb_extra_f14->sue_osc_fail_count, serial_udb_extra_f14->sue_CLOCK_CONFIG, serial_udb_extra_f14->sue_FLIGHT_PLAN_TYPE);
+}
+
/**
* @brief Send a serial_udb_extra_f14 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h
index 8779b25ff5..10c3f4ca4f 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h
@@ -65,7 +65,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f15_pack(uint8_t system_id,
* @brief Pack a serial_udb_extra_f15 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_ID_VEHICLE_MODEL_NAME Serial UDB Extra Model Name Of Vehicle
* @param sue_ID_VEHICLE_REGISTRATION Serial UDB Extra Registraton Number of Vehicle
@@ -98,7 +98,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f15_pack_chan(uint8_t system
}
/**
- * @brief Encode a serial_udb_extra_f15 struct into a message
+ * @brief Encode a serial_udb_extra_f15 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -110,6 +110,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f15_encode(uint8_t system_id
return mavlink_msg_serial_udb_extra_f15_pack(system_id, component_id, msg, serial_udb_extra_f15->sue_ID_VEHICLE_MODEL_NAME, serial_udb_extra_f15->sue_ID_VEHICLE_REGISTRATION);
}
+/**
+ * @brief Encode a serial_udb_extra_f15 struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f15 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f15_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f15_t* serial_udb_extra_f15)
+{
+ return mavlink_msg_serial_udb_extra_f15_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f15->sue_ID_VEHICLE_MODEL_NAME, serial_udb_extra_f15->sue_ID_VEHICLE_REGISTRATION);
+}
+
/**
* @brief Send a serial_udb_extra_f15 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h
index 1a173bfe44..659e6b7c52 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h
@@ -65,7 +65,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f16_pack(uint8_t system_id,
* @brief Pack a serial_udb_extra_f16 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_ID_LEAD_PILOT Serial UDB Extra Name of Expected Lead Pilot
* @param sue_ID_DIY_DRONES_URL Serial UDB Extra URL of Lead Pilot or Team
@@ -98,7 +98,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f16_pack_chan(uint8_t system
}
/**
- * @brief Encode a serial_udb_extra_f16 struct into a message
+ * @brief Encode a serial_udb_extra_f16 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -110,6 +110,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f16_encode(uint8_t system_id
return mavlink_msg_serial_udb_extra_f16_pack(system_id, component_id, msg, serial_udb_extra_f16->sue_ID_LEAD_PILOT, serial_udb_extra_f16->sue_ID_DIY_DRONES_URL);
}
+/**
+ * @brief Encode a serial_udb_extra_f16 struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f16 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f16_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f16_t* serial_udb_extra_f16)
+{
+ return mavlink_msg_serial_udb_extra_f16_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f16->sue_ID_LEAD_PILOT, serial_udb_extra_f16->sue_ID_DIY_DRONES_URL);
+}
+
/**
* @brief Send a serial_udb_extra_f16 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h
index ddfc236ba4..15ba68a346 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h
@@ -194,7 +194,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack(uint8_t system_id,
* @brief Pack a serial_udb_extra_f2_a message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_time Serial UDB Extra Time
* @param sue_status Serial UDB Extra Status
@@ -305,7 +305,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack_chan(uint8_t syste
}
/**
- * @brief Encode a serial_udb_extra_f2_a struct into a message
+ * @brief Encode a serial_udb_extra_f2_a struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -317,6 +317,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_encode(uint8_t system_i
return mavlink_msg_serial_udb_extra_f2_a_pack(system_id, component_id, msg, serial_udb_extra_f2_a->sue_time, serial_udb_extra_f2_a->sue_status, serial_udb_extra_f2_a->sue_latitude, serial_udb_extra_f2_a->sue_longitude, serial_udb_extra_f2_a->sue_altitude, serial_udb_extra_f2_a->sue_waypoint_index, serial_udb_extra_f2_a->sue_rmat0, serial_udb_extra_f2_a->sue_rmat1, serial_udb_extra_f2_a->sue_rmat2, serial_udb_extra_f2_a->sue_rmat3, serial_udb_extra_f2_a->sue_rmat4, serial_udb_extra_f2_a->sue_rmat5, serial_udb_extra_f2_a->sue_rmat6, serial_udb_extra_f2_a->sue_rmat7, serial_udb_extra_f2_a->sue_rmat8, serial_udb_extra_f2_a->sue_cog, serial_udb_extra_f2_a->sue_sog, serial_udb_extra_f2_a->sue_cpu_load, serial_udb_extra_f2_a->sue_voltage_milis, serial_udb_extra_f2_a->sue_air_speed_3DIMU, serial_udb_extra_f2_a->sue_estimated_wind_0, serial_udb_extra_f2_a->sue_estimated_wind_1, serial_udb_extra_f2_a->sue_estimated_wind_2, serial_udb_extra_f2_a->sue_magFieldEarth0, serial_udb_extra_f2_a->sue_magFieldEarth1, serial_udb_extra_f2_a->sue_magFieldEarth2, serial_udb_extra_f2_a->sue_svs, serial_udb_extra_f2_a->sue_hdop);
}
+/**
+ * @brief Encode a serial_udb_extra_f2_a struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f2_a C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f2_a_t* serial_udb_extra_f2_a)
+{
+ return mavlink_msg_serial_udb_extra_f2_a_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f2_a->sue_time, serial_udb_extra_f2_a->sue_status, serial_udb_extra_f2_a->sue_latitude, serial_udb_extra_f2_a->sue_longitude, serial_udb_extra_f2_a->sue_altitude, serial_udb_extra_f2_a->sue_waypoint_index, serial_udb_extra_f2_a->sue_rmat0, serial_udb_extra_f2_a->sue_rmat1, serial_udb_extra_f2_a->sue_rmat2, serial_udb_extra_f2_a->sue_rmat3, serial_udb_extra_f2_a->sue_rmat4, serial_udb_extra_f2_a->sue_rmat5, serial_udb_extra_f2_a->sue_rmat6, serial_udb_extra_f2_a->sue_rmat7, serial_udb_extra_f2_a->sue_rmat8, serial_udb_extra_f2_a->sue_cog, serial_udb_extra_f2_a->sue_sog, serial_udb_extra_f2_a->sue_cpu_load, serial_udb_extra_f2_a->sue_voltage_milis, serial_udb_extra_f2_a->sue_air_speed_3DIMU, serial_udb_extra_f2_a->sue_estimated_wind_0, serial_udb_extra_f2_a->sue_estimated_wind_1, serial_udb_extra_f2_a->sue_estimated_wind_2, serial_udb_extra_f2_a->sue_magFieldEarth0, serial_udb_extra_f2_a->sue_magFieldEarth1, serial_udb_extra_f2_a->sue_magFieldEarth2, serial_udb_extra_f2_a->sue_svs, serial_udb_extra_f2_a->sue_hdop);
+}
+
/**
* @brief Send a serial_udb_extra_f2_a message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h
index 74da8416d8..7cb8c87da5 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h
@@ -219,7 +219,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack(uint8_t system_id,
* @brief Pack a serial_udb_extra_f2_b message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_time Serial UDB Extra Time
* @param sue_pwm_input_1 Serial UDB Extra PWM Input Channel 1
@@ -345,7 +345,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack_chan(uint8_t syste
}
/**
- * @brief Encode a serial_udb_extra_f2_b struct into a message
+ * @brief Encode a serial_udb_extra_f2_b struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -357,6 +357,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_encode(uint8_t system_i
return mavlink_msg_serial_udb_extra_f2_b_pack(system_id, component_id, msg, serial_udb_extra_f2_b->sue_time, serial_udb_extra_f2_b->sue_pwm_input_1, serial_udb_extra_f2_b->sue_pwm_input_2, serial_udb_extra_f2_b->sue_pwm_input_3, serial_udb_extra_f2_b->sue_pwm_input_4, serial_udb_extra_f2_b->sue_pwm_input_5, serial_udb_extra_f2_b->sue_pwm_input_6, serial_udb_extra_f2_b->sue_pwm_input_7, serial_udb_extra_f2_b->sue_pwm_input_8, serial_udb_extra_f2_b->sue_pwm_input_9, serial_udb_extra_f2_b->sue_pwm_input_10, serial_udb_extra_f2_b->sue_pwm_output_1, serial_udb_extra_f2_b->sue_pwm_output_2, serial_udb_extra_f2_b->sue_pwm_output_3, serial_udb_extra_f2_b->sue_pwm_output_4, serial_udb_extra_f2_b->sue_pwm_output_5, serial_udb_extra_f2_b->sue_pwm_output_6, serial_udb_extra_f2_b->sue_pwm_output_7, serial_udb_extra_f2_b->sue_pwm_output_8, serial_udb_extra_f2_b->sue_pwm_output_9, serial_udb_extra_f2_b->sue_pwm_output_10, serial_udb_extra_f2_b->sue_imu_location_x, serial_udb_extra_f2_b->sue_imu_location_y, serial_udb_extra_f2_b->sue_imu_location_z, serial_udb_extra_f2_b->sue_flags, serial_udb_extra_f2_b->sue_osc_fails, serial_udb_extra_f2_b->sue_imu_velocity_x, serial_udb_extra_f2_b->sue_imu_velocity_y, serial_udb_extra_f2_b->sue_imu_velocity_z, serial_udb_extra_f2_b->sue_waypoint_goal_x, serial_udb_extra_f2_b->sue_waypoint_goal_y, serial_udb_extra_f2_b->sue_waypoint_goal_z, serial_udb_extra_f2_b->sue_memory_stack_free);
}
+/**
+ * @brief Encode a serial_udb_extra_f2_b struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f2_b C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f2_b_t* serial_udb_extra_f2_b)
+{
+ return mavlink_msg_serial_udb_extra_f2_b_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f2_b->sue_time, serial_udb_extra_f2_b->sue_pwm_input_1, serial_udb_extra_f2_b->sue_pwm_input_2, serial_udb_extra_f2_b->sue_pwm_input_3, serial_udb_extra_f2_b->sue_pwm_input_4, serial_udb_extra_f2_b->sue_pwm_input_5, serial_udb_extra_f2_b->sue_pwm_input_6, serial_udb_extra_f2_b->sue_pwm_input_7, serial_udb_extra_f2_b->sue_pwm_input_8, serial_udb_extra_f2_b->sue_pwm_input_9, serial_udb_extra_f2_b->sue_pwm_input_10, serial_udb_extra_f2_b->sue_pwm_output_1, serial_udb_extra_f2_b->sue_pwm_output_2, serial_udb_extra_f2_b->sue_pwm_output_3, serial_udb_extra_f2_b->sue_pwm_output_4, serial_udb_extra_f2_b->sue_pwm_output_5, serial_udb_extra_f2_b->sue_pwm_output_6, serial_udb_extra_f2_b->sue_pwm_output_7, serial_udb_extra_f2_b->sue_pwm_output_8, serial_udb_extra_f2_b->sue_pwm_output_9, serial_udb_extra_f2_b->sue_pwm_output_10, serial_udb_extra_f2_b->sue_imu_location_x, serial_udb_extra_f2_b->sue_imu_location_y, serial_udb_extra_f2_b->sue_imu_location_z, serial_udb_extra_f2_b->sue_flags, serial_udb_extra_f2_b->sue_osc_fails, serial_udb_extra_f2_b->sue_imu_velocity_x, serial_udb_extra_f2_b->sue_imu_velocity_y, serial_udb_extra_f2_b->sue_imu_velocity_z, serial_udb_extra_f2_b->sue_waypoint_goal_x, serial_udb_extra_f2_b->sue_waypoint_goal_y, serial_udb_extra_f2_b->sue_waypoint_goal_z, serial_udb_extra_f2_b->sue_memory_stack_free);
+}
+
/**
* @brief Send a serial_udb_extra_f2_b message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h
index 83ccbbedb4..77c616cc2e 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h
@@ -104,7 +104,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack(uint8_t system_id, u
* @brief Pack a serial_udb_extra_f4 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_ROLL_STABILIZATION_AILERONS Serial UDB Extra Roll Stabilization with Ailerons Enabled
* @param sue_ROLL_STABILIZATION_RUDDER Serial UDB Extra Roll Stabilization with Rudder Enabled
@@ -161,7 +161,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack_chan(uint8_t system_
}
/**
- * @brief Encode a serial_udb_extra_f4 struct into a message
+ * @brief Encode a serial_udb_extra_f4 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -173,6 +173,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f4_encode(uint8_t system_id,
return mavlink_msg_serial_udb_extra_f4_pack(system_id, component_id, msg, serial_udb_extra_f4->sue_ROLL_STABILIZATION_AILERONS, serial_udb_extra_f4->sue_ROLL_STABILIZATION_RUDDER, serial_udb_extra_f4->sue_PITCH_STABILIZATION, serial_udb_extra_f4->sue_YAW_STABILIZATION_RUDDER, serial_udb_extra_f4->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f4->sue_AILERON_NAVIGATION, serial_udb_extra_f4->sue_RUDDER_NAVIGATION, serial_udb_extra_f4->sue_ALTITUDEHOLD_STABILIZED, serial_udb_extra_f4->sue_ALTITUDEHOLD_WAYPOINT, serial_udb_extra_f4->sue_RACING_MODE);
}
+/**
+ * @brief Encode a serial_udb_extra_f4 struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f4 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f4_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f4_t* serial_udb_extra_f4)
+{
+ return mavlink_msg_serial_udb_extra_f4_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f4->sue_ROLL_STABILIZATION_AILERONS, serial_udb_extra_f4->sue_ROLL_STABILIZATION_RUDDER, serial_udb_extra_f4->sue_PITCH_STABILIZATION, serial_udb_extra_f4->sue_YAW_STABILIZATION_RUDDER, serial_udb_extra_f4->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f4->sue_AILERON_NAVIGATION, serial_udb_extra_f4->sue_RUDDER_NAVIGATION, serial_udb_extra_f4->sue_ALTITUDEHOLD_STABILIZED, serial_udb_extra_f4->sue_ALTITUDEHOLD_WAYPOINT, serial_udb_extra_f4->sue_RACING_MODE);
+}
+
/**
* @brief Send a serial_udb_extra_f4 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h
index 2b2451f00d..e115a9b445 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack(uint8_t system_id, u
* @brief Pack a serial_udb_extra_f5 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_YAWKP_AILERON Serial UDB YAWKP_AILERON Gain for Proporional control of navigation
* @param sue_YAWKD_AILERON Serial UDB YAWKD_AILERON Gain for Rate control of navigation
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack_chan(uint8_t system_
}
/**
- * @brief Encode a serial_udb_extra_f5 struct into a message
+ * @brief Encode a serial_udb_extra_f5 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f5_encode(uint8_t system_id,
return mavlink_msg_serial_udb_extra_f5_pack(system_id, component_id, msg, serial_udb_extra_f5->sue_YAWKP_AILERON, serial_udb_extra_f5->sue_YAWKD_AILERON, serial_udb_extra_f5->sue_ROLLKP, serial_udb_extra_f5->sue_ROLLKD, serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f5->sue_AILERON_BOOST);
}
+/**
+ * @brief Encode a serial_udb_extra_f5 struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f5 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f5_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f5_t* serial_udb_extra_f5)
+{
+ return mavlink_msg_serial_udb_extra_f5_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f5->sue_YAWKP_AILERON, serial_udb_extra_f5->sue_YAWKD_AILERON, serial_udb_extra_f5->sue_ROLLKP, serial_udb_extra_f5->sue_ROLLKD, serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f5->sue_AILERON_BOOST);
+}
+
/**
* @brief Send a serial_udb_extra_f5 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h
index 9d58ca9a8e..656103d090 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f6_pack(uint8_t system_id, u
* @brief Pack a serial_udb_extra_f6 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_PITCHGAIN Serial UDB Extra PITCHGAIN Proportional Control
* @param sue_PITCHKD Serial UDB Extra Pitch Rate Control
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f6_pack_chan(uint8_t system_
}
/**
- * @brief Encode a serial_udb_extra_f6 struct into a message
+ * @brief Encode a serial_udb_extra_f6 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f6_encode(uint8_t system_id,
return mavlink_msg_serial_udb_extra_f6_pack(system_id, component_id, msg, serial_udb_extra_f6->sue_PITCHGAIN, serial_udb_extra_f6->sue_PITCHKD, serial_udb_extra_f6->sue_RUDDER_ELEV_MIX, serial_udb_extra_f6->sue_ROLL_ELEV_MIX, serial_udb_extra_f6->sue_ELEVATOR_BOOST);
}
+/**
+ * @brief Encode a serial_udb_extra_f6 struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f6 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f6_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f6_t* serial_udb_extra_f6)
+{
+ return mavlink_msg_serial_udb_extra_f6_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f6->sue_PITCHGAIN, serial_udb_extra_f6->sue_PITCHKD, serial_udb_extra_f6->sue_RUDDER_ELEV_MIX, serial_udb_extra_f6->sue_ROLL_ELEV_MIX, serial_udb_extra_f6->sue_ELEVATOR_BOOST);
+}
+
/**
* @brief Send a serial_udb_extra_f6 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h
index ab73b967e0..51c98e6b7a 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack(uint8_t system_id, u
* @brief Pack a serial_udb_extra_f7 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_YAWKP_RUDDER Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation
* @param sue_YAWKD_RUDDER Serial UDB YAWKD_RUDDER Gain for Rate control of navigation
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack_chan(uint8_t system_
}
/**
- * @brief Encode a serial_udb_extra_f7 struct into a message
+ * @brief Encode a serial_udb_extra_f7 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f7_encode(uint8_t system_id,
return mavlink_msg_serial_udb_extra_f7_pack(system_id, component_id, msg, serial_udb_extra_f7->sue_YAWKP_RUDDER, serial_udb_extra_f7->sue_YAWKD_RUDDER, serial_udb_extra_f7->sue_ROLLKP_RUDDER, serial_udb_extra_f7->sue_ROLLKD_RUDDER, serial_udb_extra_f7->sue_RUDDER_BOOST, serial_udb_extra_f7->sue_RTL_PITCH_DOWN);
}
+/**
+ * @brief Encode a serial_udb_extra_f7 struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f7 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f7_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f7_t* serial_udb_extra_f7)
+{
+ return mavlink_msg_serial_udb_extra_f7_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f7->sue_YAWKP_RUDDER, serial_udb_extra_f7->sue_YAWKD_RUDDER, serial_udb_extra_f7->sue_ROLLKP_RUDDER, serial_udb_extra_f7->sue_ROLLKD_RUDDER, serial_udb_extra_f7->sue_RUDDER_BOOST, serial_udb_extra_f7->sue_RTL_PITCH_DOWN);
+}
+
/**
* @brief Send a serial_udb_extra_f7 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h
index 310246e8e7..8557a95e27 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack(uint8_t system_id, u
* @brief Pack a serial_udb_extra_f8 message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param sue_HEIGHT_TARGET_MAX Serial UDB Extra HEIGHT_TARGET_MAX
* @param sue_HEIGHT_TARGET_MIN Serial UDB Extra HEIGHT_TARGET_MIN
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack_chan(uint8_t system_
}
/**
- * @brief Encode a serial_udb_extra_f8 struct into a message
+ * @brief Encode a serial_udb_extra_f8 struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_serial_udb_extra_f8_encode(uint8_t system_id,
return mavlink_msg_serial_udb_extra_f8_pack(system_id, component_id, msg, serial_udb_extra_f8->sue_HEIGHT_TARGET_MAX, serial_udb_extra_f8->sue_HEIGHT_TARGET_MIN, serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MIN, serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MAX, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MIN, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MAX, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_HIGH);
}
+/**
+ * @brief Encode a serial_udb_extra_f8 struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param serial_udb_extra_f8 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_serial_udb_extra_f8_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f8_t* serial_udb_extra_f8)
+{
+ return mavlink_msg_serial_udb_extra_f8_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f8->sue_HEIGHT_TARGET_MAX, serial_udb_extra_f8->sue_HEIGHT_TARGET_MIN, serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MIN, serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MAX, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MIN, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MAX, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_HIGH);
+}
+
/**
* @brief Send a serial_udb_extra_f8 message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/version.h b/mavlink/include/mavlink/v1.0/matrixpilot/version.h
index ea0265298b..59f3d2ded2 100644
--- a/mavlink/include/mavlink/v1.0/matrixpilot/version.h
+++ b/mavlink/include/mavlink/v1.0/matrixpilot/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Thu Jul 4 13:11:50 2013"
+#define MAVLINK_BUILD_DATE "Tue Sep 10 23:49:51 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
diff --git a/mavlink/include/mavlink/v1.0/mavlink_conversions.h b/mavlink/include/mavlink/v1.0/mavlink_conversions.h
index d893635770..51afac87c3 100644
--- a/mavlink/include/mavlink/v1.0/mavlink_conversions.h
+++ b/mavlink/include/mavlink/v1.0/mavlink_conversions.h
@@ -9,6 +9,10 @@
#endif
#include
+#ifndef M_PI_2
+ #define M_PI_2 ((float)asin(1))
+#endif
+
/**
* @file mavlink_conversions.h
*
@@ -49,12 +53,12 @@ MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, flo
float phi, theta, psi;
theta = asin(-dcm[2][0]);
- if (fabs(theta - M_PI_2) < 1.0e-3f) {
+ if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) {
phi = 0.0f;
- psi = (atan2(dcm[1][2] - dcm[0][1],
+ psi = (atan2f(dcm[1][2] - dcm[0][1],
dcm[0][2] + dcm[1][1]) + phi);
- } else if (fabs(theta + M_PI_2) < 1.0e-3f) {
+ } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) {
phi = 0.0f;
psi = atan2f(dcm[1][2] - dcm[0][1],
dcm[0][2] + dcm[1][1] - phi);
@@ -128,4 +132,4 @@ MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, flo
dcm[2][2] = cosPhi * cosThe;
}
-#endif
\ No newline at end of file
+#endif
diff --git a/mavlink/include/mavlink/v1.0/mavlink_helpers.h b/mavlink/include/mavlink/v1.0/mavlink_helpers.h
index 72cf91fb9f..96672f847f 100644
--- a/mavlink/include/mavlink/v1.0/mavlink_helpers.h
+++ b/mavlink/include/mavlink/v1.0/mavlink_helpers.h
@@ -16,7 +16,12 @@
#ifndef MAVLINK_GET_CHANNEL_STATUS
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
{
+#if MAVLINK_EXTERNAL_RX_STATUS
+ // No m_mavlink_status array defined in function,
+ // has to be defined externally
+#else
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
+#endif
return &m_mavlink_status[chan];
}
#endif
@@ -29,11 +34,8 @@ MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
{
#if MAVLINK_EXTERNAL_RX_BUFFER
- // No m_mavlink_message array defined in function,
+ // No m_mavlink_buffer array defined in function,
// has to be defined externally
-#ifndef m_mavlink_message
-#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];)
-#endif
#else
static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
#endif
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h
index 1aac8395df..ef5354d5e1 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h
@@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint
* @brief Pack a attitude_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target The system to be controlled
* @param roll roll
@@ -153,7 +153,7 @@ static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a attitude_control struct into a message
+ * @brief Encode a attitude_control struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -165,6 +165,20 @@ static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, ui
return mavlink_msg_attitude_control_pack(system_id, component_id, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual);
}
+/**
+ * @brief Encode a attitude_control struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param attitude_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_control_t* attitude_control)
+{
+ return mavlink_msg_attitude_control_pack_chan(system_id, component_id, chan, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual);
+}
+
/**
* @brief Send a attitude_control message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h
index 353e105814..d41093792e 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h
@@ -92,7 +92,7 @@ static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t
* @brief Pack a brief_feature message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param x x position in m
* @param y y position in m
@@ -141,7 +141,7 @@ static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, ui
}
/**
- * @brief Encode a brief_feature struct into a message
+ * @brief Encode a brief_feature struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -153,6 +153,20 @@ static inline uint16_t mavlink_msg_brief_feature_encode(uint8_t system_id, uint8
return mavlink_msg_brief_feature_pack(system_id, component_id, msg, brief_feature->x, brief_feature->y, brief_feature->z, brief_feature->orientation_assignment, brief_feature->size, brief_feature->orientation, brief_feature->descriptor, brief_feature->response);
}
+/**
+ * @brief Encode a brief_feature 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 brief_feature C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_brief_feature_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_brief_feature_t* brief_feature)
+{
+ return mavlink_msg_brief_feature_pack_chan(system_id, component_id, chan, msg, brief_feature->x, brief_feature->y, brief_feature->z, brief_feature->orientation_assignment, brief_feature->size, brief_feature->orientation, brief_feature->descriptor, brief_feature->response);
+}
+
/**
* @brief Send a brief_feature message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h
index 5251c35c32..a7af8c8ebb 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t syst
* @brief Pack a data_transmission_handshake message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @param size total data size in bytes (set on ACK only)
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t
}
/**
- * @brief Encode a data_transmission_handshake struct into a message
+ * @brief Encode a data_transmission_handshake struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t sy
return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality);
}
+/**
+ * @brief Encode a data_transmission_handshake 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 data_transmission_handshake C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake)
+{
+ return mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, chan, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality);
+}
+
/**
* @brief Send a data_transmission_handshake message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h
index feeef6f398..40001dc309 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_encapsulated_data.h
@@ -62,7 +62,7 @@ static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uin
* @brief Pack a encapsulated_data message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param seqnr sequence number (starting with 0 on every transmission)
* @param data image data bytes
@@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a encapsulated_data struct into a message
+ * @brief Encode a encapsulated_data struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -105,6 +105,20 @@ static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, u
return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data);
}
+/**
+ * @brief Encode a encapsulated_data 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 encapsulated_data C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_encapsulated_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data)
+{
+ return mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, chan, msg, encapsulated_data->seqnr, encapsulated_data->data);
+}
+
/**
* @brief Send a encapsulated_data message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h
index 6d1d9cca76..ae4db825df 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h
@@ -169,7 +169,7 @@ static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8
* @brief Pack a image_available message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param cam_id Camera id
* @param cam_no Camera # (starts with 0)
@@ -265,7 +265,7 @@ static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a image_available struct into a message
+ * @brief Encode a image_available struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -277,6 +277,20 @@ static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uin
return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt, image_available->ground_x, image_available->ground_y, image_available->ground_z);
}
+/**
+ * @brief Encode a image_available 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 image_available C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_image_available_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_image_available_t* image_available)
+{
+ return mavlink_msg_image_available_pack_chan(system_id, component_id, chan, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt, image_available->ground_x, image_available->ground_y, image_available->ground_z);
+}
+
/**
* @brief Send a image_available message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h
index 784cedf8b5..664574be94 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h
@@ -59,7 +59,7 @@ static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id,
* @brief Pack a image_trigger_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param enable 0 to disable, 1 to enable
* @return length of the message in bytes (excluding serial stream start sign)
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_image_trigger_control_pack_chan(uint8_t syste
}
/**
- * @brief Encode a image_trigger_control struct into a message
+ * @brief Encode a image_trigger_control struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -101,6 +101,20 @@ static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_i
return mavlink_msg_image_trigger_control_pack(system_id, component_id, msg, image_trigger_control->enable);
}
+/**
+ * @brief Encode a image_trigger_control struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param image_trigger_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_image_trigger_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_image_trigger_control_t* image_trigger_control)
+{
+ return mavlink_msg_image_trigger_control_pack_chan(system_id, component_id, chan, msg, image_trigger_control->enable);
+}
+
/**
* @brief Send a image_trigger_control message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h
index 05b0d775fd..f3a2243afc 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h
@@ -114,7 +114,7 @@ static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8
* @brief Pack a image_triggered message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param timestamp Timestamp
* @param seq IMU seq
@@ -177,7 +177,7 @@ static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a image_triggered struct into a message
+ * @brief Encode a image_triggered struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -189,6 +189,20 @@ static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uin
return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt, image_triggered->ground_x, image_triggered->ground_y, image_triggered->ground_z);
}
+/**
+ * @brief Encode a image_triggered 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 image_triggered C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_image_triggered_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered)
+{
+ return mavlink_msg_image_triggered_pack_chan(system_id, component_id, chan, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt, image_triggered->ground_x, image_triggered->ground_y, image_triggered->ground_z);
+}
+
/**
* @brief Send a image_triggered message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h
index 817ec60a20..6bdcceaf9a 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t compon
* @brief Pack a marker message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param id ID
* @param x x position
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t c
}
/**
- * @brief Encode a marker struct into a message
+ * @brief Encode a marker struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t comp
return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw);
}
+/**
+ * @brief Encode a marker 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 marker C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_marker_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_marker_t* marker)
+{
+ return mavlink_msg_marker_pack_chan(system_id, component_id, chan, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw);
+}
+
/**
* @brief Send a marker message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h
index 7e29d71525..aa7b827a36 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h
@@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint
* @brief Pack a pattern_detected message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type 0: Pattern, 1: Letter
* @param confidence Confidence of detection
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a pattern_detected struct into a message
+ * @brief Encode a pattern_detected struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -121,6 +121,20 @@ static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, ui
return mavlink_msg_pattern_detected_pack(system_id, component_id, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected);
}
+/**
+ * @brief Encode a pattern_detected 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 pattern_detected C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_pattern_detected_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pattern_detected_t* pattern_detected)
+{
+ return mavlink_msg_pattern_detected_pack_chan(system_id, component_id, chan, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected);
+}
+
/**
* @brief Send a pattern_detected message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h
index a6faebbb5a..913a52897e 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h
@@ -92,7 +92,7 @@ static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uin
* @brief Pack a point_of_interest message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
* @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
@@ -141,7 +141,7 @@ static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a point_of_interest struct into a message
+ * @brief Encode a point_of_interest struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -153,6 +153,20 @@ static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, u
return mavlink_msg_point_of_interest_pack(system_id, component_id, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name);
}
+/**
+ * @brief Encode a point_of_interest 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 point_of_interest C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_point_of_interest_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_point_of_interest_t* point_of_interest)
+{
+ return mavlink_msg_point_of_interest_pack_chan(system_id, component_id, chan, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name);
+}
+
/**
* @brief Send a point_of_interest message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h
index 8d02f9e5c4..e244364318 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h
@@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t sys
* @brief Pack a point_of_interest_connection message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
* @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
@@ -165,7 +165,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_
}
/**
- * @brief Encode a point_of_interest_connection struct into a message
+ * @brief Encode a point_of_interest_connection struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -177,6 +177,20 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t s
return mavlink_msg_point_of_interest_connection_pack(system_id, component_id, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name);
}
+/**
+ * @brief Encode a point_of_interest_connection 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 point_of_interest_connection C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_point_of_interest_connection_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_point_of_interest_connection_t* point_of_interest_connection)
+{
+ return mavlink_msg_point_of_interest_connection_pack_chan(system_id, component_id, chan, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name);
+}
+
/**
* @brief Send a point_of_interest_connection message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h
index 6c86be3ab5..6f4ca510ae 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system
* @brief Pack a position_control_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param id ID of waypoint, 0 for plain position
* @param x x position
@@ -121,7 +121,7 @@ static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t s
}
/**
- * @brief Encode a position_control_setpoint struct into a message
+ * @brief Encode a position_control_setpoint struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -133,6 +133,20 @@ static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t syst
return mavlink_msg_position_control_setpoint_pack(system_id, component_id, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw);
}
+/**
+ * @brief Encode a position_control_setpoint 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 position_control_setpoint C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_position_control_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_control_setpoint_t* position_control_setpoint)
+{
+ return mavlink_msg_position_control_setpoint_pack_chan(system_id, component_id, chan, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw);
+}
+
/**
* @brief Send a position_control_setpoint message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h
index 0a0dbdb378..08cedbb4b2 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t compo
* @brief Pack a raw_aux message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
* @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a raw_aux struct into a message
+ * @brief Encode a raw_aux struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t com
return mavlink_msg_raw_aux_pack(system_id, component_id, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro);
}
+/**
+ * @brief Encode a raw_aux 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 raw_aux C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_raw_aux_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux)
+{
+ return mavlink_msg_raw_aux_pack_chan(system_id, component_id, chan, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro);
+}
+
/**
* @brief Send a raw_aux message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h
index 7be6409119..b26d748c25 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8
* @brief Pack a set_cam_shutter message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param cam_no Camera id
* @param cam_mode Camera mode: 0 = auto, 1 = manual
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a set_cam_shutter struct into a message
+ * @brief Encode a set_cam_shutter struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uin
return mavlink_msg_set_cam_shutter_pack(system_id, component_id, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain);
}
+/**
+ * @brief Encode a set_cam_shutter 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 set_cam_shutter C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_cam_shutter_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter)
+{
+ return mavlink_msg_set_cam_shutter_pack_chan(system_id, component_id, chan, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain);
+}
+
/**
* @brief Send a set_cam_shutter message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h
index 25bff659ed..f1f9e698f8 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_set_position_control_offset_pack(uint8_t syst
* @brief Pack a set_position_control_offset message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_set_position_control_offset_pack_chan(uint8_t
}
/**
- * @brief Encode a set_position_control_offset struct into a message
+ * @brief Encode a set_position_control_offset struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_set_position_control_offset_encode(uint8_t sy
return mavlink_msg_set_position_control_offset_pack(system_id, component_id, msg, set_position_control_offset->target_system, set_position_control_offset->target_component, set_position_control_offset->x, set_position_control_offset->y, set_position_control_offset->z, set_position_control_offset->yaw);
}
+/**
+ * @brief Encode a set_position_control_offset 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 set_position_control_offset C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_position_control_offset_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_control_offset_t* set_position_control_offset)
+{
+ return mavlink_msg_set_position_control_offset_pack_chan(system_id, component_id, chan, msg, set_position_control_offset->target_system, set_position_control_offset->target_component, set_position_control_offset->x, set_position_control_offset->y, set_position_control_offset->z, set_position_control_offset->yaw);
+}
+
/**
* @brief Send a set_position_control_offset message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h
index 4267880186..9458087da9 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h
@@ -74,7 +74,7 @@ static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint
* @brief Pack a watchdog_command message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system_id Target system ID
* @param watchdog_id Watchdog ID
@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a watchdog_command struct into a message
+ * @brief Encode a watchdog_command struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -125,6 +125,20 @@ static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, ui
return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id);
}
+/**
+ * @brief Encode a watchdog_command 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 watchdog_command C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_watchdog_command_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command)
+{
+ return mavlink_msg_watchdog_command_pack_chan(system_id, component_id, chan, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id);
+}
+
/**
* @brief Send a watchdog_command message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h
index 49478999ce..3f4295ee5d 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, ui
* @brief Pack a watchdog_heartbeat message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param watchdog_id Watchdog ID
* @param process_count Number of processes
@@ -97,7 +97,7 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_i
}
/**
- * @brief Encode a watchdog_heartbeat struct into a message
+ * @brief Encode a watchdog_heartbeat struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -109,6 +109,20 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id,
return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count);
}
+/**
+ * @brief Encode a watchdog_heartbeat 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 watchdog_heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_watchdog_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
+{
+ return mavlink_msg_watchdog_heartbeat_pack_chan(system_id, component_id, chan, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count);
+}
+
/**
* @brief Send a watchdog_heartbeat message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h
index d706ef85e1..55853cdde4 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h
@@ -78,7 +78,7 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id,
* @brief Pack a watchdog_process_info message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param watchdog_id Watchdog ID
* @param process_id Process ID
@@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t syste
}
/**
- * @brief Encode a watchdog_process_info struct into a message
+ * @brief Encode a watchdog_process_info struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -130,6 +130,20 @@ static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_i
return mavlink_msg_watchdog_process_info_pack(system_id, component_id, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout);
}
+/**
+ * @brief Encode a watchdog_process_info 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 watchdog_process_info C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_watchdog_process_info_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info)
+{
+ return mavlink_msg_watchdog_process_info_pack_chan(system_id, component_id, chan, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout);
+}
+
/**
* @brief Send a watchdog_process_info message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h
index b1bbaaae7b..a0410d803e 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h
@@ -84,7 +84,7 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_i
* @brief Pack a watchdog_process_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 was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param watchdog_id Watchdog ID
* @param process_id Process ID
@@ -129,7 +129,7 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t sys
}
/**
- * @brief Encode a watchdog_process_status struct into a message
+ * @brief Encode a watchdog_process_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -141,6 +141,20 @@ static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system
return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes);
}
+/**
+ * @brief Encode a watchdog_process_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 watchdog_process_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_watchdog_process_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status)
+{
+ return mavlink_msg_watchdog_process_status_pack_chan(system_id, component_id, chan, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes);
+}
+
/**
* @brief Send a watchdog_process_status message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h
index a2d0d0e14e..3fc9e64773 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h
@@ -72,6 +72,7 @@ enum MAV_CMD
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
@@ -80,7 +81,8 @@ enum MAV_CMD
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
- MAV_CMD_ENUM_END=401, /* | */
+ MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
+ MAV_CMD_ENUM_END=501, /* | */
MAV_CMD_DO_START_SEARCH=10001, /* Starts a search |1 to arm, 0 to disarm| */
MAV_CMD_DO_FINISH_SEARCH=10002, /* Starts a search |1 to arm, 0 to disarm| */
MAV_CMD_NAV_SWEEP=10003, /* Starts a search |1 to arm, 0 to disarm| */
diff --git a/mavlink/include/mavlink/v1.0/pixhawk/version.h b/mavlink/include/mavlink/v1.0/pixhawk/version.h
index 61fe6e930d..07831a4256 100644
--- a/mavlink/include/mavlink/v1.0/pixhawk/version.h
+++ b/mavlink/include/mavlink/v1.0/pixhawk/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Thu Jul 4 13:12:05 2013"
+#define MAVLINK_BUILD_DATE "Tue Sep 10 23:49:13 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
diff --git a/mavlink/include/mavlink/v1.0/protocol.h b/mavlink/include/mavlink/v1.0/protocol.h
index ddacae59c4..86e7ff588b 100644
--- a/mavlink/include/mavlink/v1.0/protocol.h
+++ b/mavlink/include/mavlink/v1.0/protocol.h
@@ -162,7 +162,7 @@ static inline void byte_copy_8(char *dst, const char *src)
/*
like memcpy(), but if src is NULL, do a memset to zero
*/
-static void mav_array_memcpy(void *dest, const void *src, size_t n)
+static inline void mav_array_memcpy(void *dest, const void *src, size_t n)
{
if (src == NULL) {
memset(dest, 0, n);
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h
index 5cdd584561..73e9d75dbc 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h
@@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack(uint8_t system_id, uint
* @brief Pack a cmd_airspeed_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param spCmd
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a cmd_airspeed_ack struct into a message
+ * @brief Encode a cmd_airspeed_ack struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -121,6 +121,20 @@ static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode(uint8_t system_id, ui
return mavlink_msg_cmd_airspeed_ack_pack(system_id, component_id, msg, cmd_airspeed_ack->spCmd, cmd_airspeed_ack->ack);
}
+/**
+ * @brief Encode a cmd_airspeed_ack 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 cmd_airspeed_ack C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack)
+{
+ return mavlink_msg_cmd_airspeed_ack_pack_chan(system_id, component_id, chan, msg, cmd_airspeed_ack->spCmd, cmd_airspeed_ack->ack);
+}
+
/**
* @brief Send a cmd_airspeed_ack message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h
index 2a4894fe72..b6b567f993 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h
@@ -72,7 +72,7 @@ static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack(uint8_t system_id, uin
* @brief Pack a cmd_airspeed_chng message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target
@@ -109,7 +109,7 @@ static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack_chan(uint8_t system_id
}
/**
- * @brief Encode a cmd_airspeed_chng struct into a message
+ * @brief Encode a cmd_airspeed_chng struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -121,6 +121,20 @@ static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode(uint8_t system_id, u
return mavlink_msg_cmd_airspeed_chng_pack(system_id, component_id, msg, cmd_airspeed_chng->target, cmd_airspeed_chng->spCmd);
}
+/**
+ * @brief Encode a cmd_airspeed_chng 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 cmd_airspeed_chng C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng)
+{
+ return mavlink_msg_cmd_airspeed_chng_pack_chan(system_id, component_id, chan, msg, cmd_airspeed_chng->target, cmd_airspeed_chng->spCmd);
+}
+
/**
* @brief Send a cmd_airspeed_chng message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h
index d600e91749..642f7aab93 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h
@@ -63,7 +63,7 @@ static inline uint16_t mavlink_msg_filt_rot_vel_pack(uint8_t system_id, uint8_t
* @brief Pack a filt_rot_vel message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param rotVel
@@ -95,7 +95,7 @@ static inline uint16_t mavlink_msg_filt_rot_vel_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a filt_rot_vel struct into a message
+ * @brief Encode a filt_rot_vel struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -107,6 +107,20 @@ static inline uint16_t mavlink_msg_filt_rot_vel_encode(uint8_t system_id, uint8_
return mavlink_msg_filt_rot_vel_pack(system_id, component_id, msg, filt_rot_vel->rotVel);
}
+/**
+ * @brief Encode a filt_rot_vel 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 filt_rot_vel C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_filt_rot_vel_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_filt_rot_vel_t* filt_rot_vel)
+{
+ return mavlink_msg_filt_rot_vel_pack_chan(system_id, component_id, chan, msg, filt_rot_vel->rotVel);
+}
+
/**
* @brief Send a filt_rot_vel message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h
index cb1c86f436..0f8369881a 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h
@@ -73,7 +73,7 @@ static inline uint16_t mavlink_msg_llc_out_pack(uint8_t system_id, uint8_t compo
* @brief Pack a llc_out message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param servoOut
@@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_llc_out_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a llc_out struct into a message
+ * @brief Encode a llc_out struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -122,6 +122,20 @@ static inline uint16_t mavlink_msg_llc_out_encode(uint8_t system_id, uint8_t com
return mavlink_msg_llc_out_pack(system_id, component_id, msg, llc_out->servoOut, llc_out->MotorOut);
}
+/**
+ * @brief Encode a llc_out 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 llc_out C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_llc_out_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_llc_out_t* llc_out)
+{
+ return mavlink_msg_llc_out_pack_chan(system_id, component_id, chan, msg, llc_out->servoOut, llc_out->MotorOut);
+}
+
/**
* @brief Send a llc_out message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h
index b6bd0d9e52..5d93823262 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h
@@ -63,7 +63,7 @@ static inline uint16_t mavlink_msg_obs_air_temp_pack(uint8_t system_id, uint8_t
* @brief Pack a obs_air_temp message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param airT
@@ -95,7 +95,7 @@ static inline uint16_t mavlink_msg_obs_air_temp_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a obs_air_temp struct into a message
+ * @brief Encode a obs_air_temp struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -107,6 +107,20 @@ static inline uint16_t mavlink_msg_obs_air_temp_encode(uint8_t system_id, uint8_
return mavlink_msg_obs_air_temp_pack(system_id, component_id, msg, obs_air_temp->airT);
}
+/**
+ * @brief Encode a obs_air_temp 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 obs_air_temp C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obs_air_temp_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_air_temp_t* obs_air_temp)
+{
+ return mavlink_msg_obs_air_temp_pack_chan(system_id, component_id, chan, msg, obs_air_temp->airT);
+}
+
/**
* @brief Send a obs_air_temp message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h
index 87a65cfa06..35d813ca15 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h
@@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_obs_air_velocity_pack(uint8_t system_id, uint
* @brief Pack a obs_air_velocity message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param magnitude
@@ -123,7 +123,7 @@ static inline uint16_t mavlink_msg_obs_air_velocity_pack_chan(uint8_t system_id,
}
/**
- * @brief Encode a obs_air_velocity struct into a message
+ * @brief Encode a obs_air_velocity struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -135,6 +135,20 @@ static inline uint16_t mavlink_msg_obs_air_velocity_encode(uint8_t system_id, ui
return mavlink_msg_obs_air_velocity_pack(system_id, component_id, msg, obs_air_velocity->magnitude, obs_air_velocity->aoa, obs_air_velocity->slip);
}
+/**
+ * @brief Encode a obs_air_velocity 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 obs_air_velocity C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obs_air_velocity_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_air_velocity_t* obs_air_velocity)
+{
+ return mavlink_msg_obs_air_velocity_pack_chan(system_id, component_id, chan, msg, obs_air_velocity->magnitude, obs_air_velocity->aoa, obs_air_velocity->slip);
+}
+
/**
* @brief Send a obs_air_velocity message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h
index 602eafc80b..9c80cd66eb 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h
@@ -63,7 +63,7 @@ static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t
* @brief Pack a obs_attitude message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param quat
@@ -95,7 +95,7 @@ static inline uint16_t mavlink_msg_obs_attitude_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a obs_attitude struct into a message
+ * @brief Encode a obs_attitude struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -107,6 +107,20 @@ static inline uint16_t mavlink_msg_obs_attitude_encode(uint8_t system_id, uint8_
return mavlink_msg_obs_attitude_pack(system_id, component_id, msg, obs_attitude->quat);
}
+/**
+ * @brief Encode a obs_attitude 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 obs_attitude C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obs_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_attitude_t* obs_attitude)
+{
+ return mavlink_msg_obs_attitude_pack_chan(system_id, component_id, chan, msg, obs_attitude->quat);
+}
+
/**
* @brief Send a obs_attitude message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h
index 3ab855ba81..24dd43b579 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h
@@ -73,7 +73,7 @@ static inline uint16_t mavlink_msg_obs_bias_pack(uint8_t system_id, uint8_t comp
* @brief Pack a obs_bias message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param accBias
@@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_obs_bias_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a obs_bias struct into a message
+ * @brief Encode a obs_bias struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -122,6 +122,20 @@ static inline uint16_t mavlink_msg_obs_bias_encode(uint8_t system_id, uint8_t co
return mavlink_msg_obs_bias_pack(system_id, component_id, msg, obs_bias->accBias, obs_bias->gyroBias);
}
+/**
+ * @brief Encode a obs_bias 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 obs_bias C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obs_bias_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_bias_t* obs_bias)
+{
+ return mavlink_msg_obs_bias_pack_chan(system_id, component_id, chan, msg, obs_bias->accBias, obs_bias->gyroBias);
+}
+
/**
* @brief Send a obs_bias message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h
index ec494d51a2..cfc2fe7e10 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h
@@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_obs_position_pack(uint8_t system_id, uint8_t
* @brief Pack a obs_position message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param lon
@@ -123,7 +123,7 @@ static inline uint16_t mavlink_msg_obs_position_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a obs_position struct into a message
+ * @brief Encode a obs_position struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -135,6 +135,20 @@ static inline uint16_t mavlink_msg_obs_position_encode(uint8_t system_id, uint8_
return mavlink_msg_obs_position_pack(system_id, component_id, msg, obs_position->lon, obs_position->lat, obs_position->alt);
}
+/**
+ * @brief Encode a obs_position 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 obs_position C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obs_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_position_t* obs_position)
+{
+ return mavlink_msg_obs_position_pack_chan(system_id, component_id, chan, msg, obs_position->lon, obs_position->lat, obs_position->alt);
+}
+
/**
* @brief Send a obs_position message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h
index e42b0261fa..24e272bf7a 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h
@@ -63,7 +63,7 @@ static inline uint16_t mavlink_msg_obs_qff_pack(uint8_t system_id, uint8_t compo
* @brief Pack a obs_qff message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param qff
@@ -95,7 +95,7 @@ static inline uint16_t mavlink_msg_obs_qff_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a obs_qff struct into a message
+ * @brief Encode a obs_qff struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -107,6 +107,20 @@ static inline uint16_t mavlink_msg_obs_qff_encode(uint8_t system_id, uint8_t com
return mavlink_msg_obs_qff_pack(system_id, component_id, msg, obs_qff->qff);
}
+/**
+ * @brief Encode a obs_qff 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 obs_qff C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obs_qff_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_qff_t* obs_qff)
+{
+ return mavlink_msg_obs_qff_pack_chan(system_id, component_id, chan, msg, obs_qff->qff);
+}
+
/**
* @brief Send a obs_qff message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h
index 2fa6e9111f..6e3776632b 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h
@@ -63,7 +63,7 @@ static inline uint16_t mavlink_msg_obs_velocity_pack(uint8_t system_id, uint8_t
* @brief Pack a obs_velocity message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param vel
@@ -95,7 +95,7 @@ static inline uint16_t mavlink_msg_obs_velocity_pack_chan(uint8_t system_id, uin
}
/**
- * @brief Encode a obs_velocity struct into a message
+ * @brief Encode a obs_velocity struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -107,6 +107,20 @@ static inline uint16_t mavlink_msg_obs_velocity_encode(uint8_t system_id, uint8_
return mavlink_msg_obs_velocity_pack(system_id, component_id, msg, obs_velocity->vel);
}
+/**
+ * @brief Encode a obs_velocity 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 obs_velocity C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obs_velocity_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_velocity_t* obs_velocity)
+{
+ return mavlink_msg_obs_velocity_pack_chan(system_id, component_id, chan, msg, obs_velocity->vel);
+}
+
/**
* @brief Send a obs_velocity message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h
index bc9f6e4eff..55f7cb2ae1 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h
@@ -63,7 +63,7 @@ static inline uint16_t mavlink_msg_obs_wind_pack(uint8_t system_id, uint8_t comp
* @brief Pack a obs_wind message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param wind
@@ -95,7 +95,7 @@ static inline uint16_t mavlink_msg_obs_wind_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a obs_wind struct into a message
+ * @brief Encode a obs_wind struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -107,6 +107,20 @@ static inline uint16_t mavlink_msg_obs_wind_encode(uint8_t system_id, uint8_t co
return mavlink_msg_obs_wind_pack(system_id, component_id, msg, obs_wind->wind);
}
+/**
+ * @brief Encode a obs_wind 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 obs_wind C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obs_wind_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_wind_t* obs_wind)
+{
+ return mavlink_msg_obs_wind_pack_chan(system_id, component_id, chan, msg, obs_wind->wind);
+}
+
/**
* @brief Send a obs_wind message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h
index 0799af07f8..e0963ece79 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h
@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_pm_elec_pack(uint8_t system_id, uint8_t compo
* @brief Pack a pm_elec message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param PwCons
@@ -119,7 +119,7 @@ static inline uint16_t mavlink_msg_pm_elec_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a pm_elec struct into a message
+ * @brief Encode a pm_elec struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -131,6 +131,20 @@ static inline uint16_t mavlink_msg_pm_elec_encode(uint8_t system_id, uint8_t com
return mavlink_msg_pm_elec_pack(system_id, component_id, msg, pm_elec->PwCons, pm_elec->BatStat, pm_elec->PwGen);
}
+/**
+ * @brief Encode a pm_elec 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 pm_elec C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_pm_elec_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pm_elec_t* pm_elec)
+{
+ return mavlink_msg_pm_elec_pack_chan(system_id, component_id, chan, msg, pm_elec->PwCons, pm_elec->BatStat, pm_elec->PwGen);
+}
+
/**
* @brief Send a pm_elec message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h
index e5e483a73a..94f3e58bb9 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h
@@ -90,7 +90,7 @@ static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t comp
* @brief Pack a sys_stat message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
- * @param chan The MAVLink channel this message was sent over
+ * @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param gps
@@ -137,7 +137,7 @@ static inline uint16_t mavlink_msg_sys_stat_pack_chan(uint8_t system_id, uint8_t
}
/**
- * @brief Encode a sys_stat struct into a message
+ * @brief Encode a sys_stat struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
@@ -149,6 +149,20 @@ static inline uint16_t mavlink_msg_sys_stat_encode(uint8_t system_id, uint8_t co
return mavlink_msg_sys_stat_pack(system_id, component_id, msg, sys_stat->gps, sys_stat->act, sys_stat->mod, sys_stat->commRssi);
}
+/**
+ * @brief Encode a sys_stat 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 sys_stat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sys_stat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_stat_t* sys_stat)
+{
+ return mavlink_msg_sys_stat_pack_chan(system_id, component_id, chan, msg, sys_stat->gps, sys_stat->act, sys_stat->mod, sys_stat->commRssi);
+}
+
/**
* @brief Send a sys_stat message
* @param chan MAVLink channel to send the message
diff --git a/mavlink/include/mavlink/v1.0/sensesoar/version.h b/mavlink/include/mavlink/v1.0/sensesoar/version.h
index 4633e6eb5c..ab3f47b9df 100644
--- a/mavlink/include/mavlink/v1.0/sensesoar/version.h
+++ b/mavlink/include/mavlink/v1.0/sensesoar/version.h
@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Thu Jul 4 13:12:22 2013"
+#define MAVLINK_BUILD_DATE "Tue Sep 10 23:50:02 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
diff --git a/misc/tones/charge.txt b/misc/tones/charge.txt
new file mode 100644
index 0000000000..cf33c58b3e
--- /dev/null
+++ b/misc/tones/charge.txt
@@ -0,0 +1 @@
+MFT90O3C16.C32C16.C32C16.C32G16.E32G16.E32G16.E32C16.C32C16.C32C16.C32G16.E32G16.E32G16.E32C4
\ No newline at end of file
diff --git a/misc/tones/cucuracha.txt b/misc/tones/cucuracha.txt
new file mode 100644
index 0000000000..dce328c03b
--- /dev/null
+++ b/misc/tones/cucuracha.txt
@@ -0,0 +1 @@
+MFT90O2C16C16C16F8.A8C16C16C16F8.A4P16P8
\ No newline at end of file
diff --git a/misc/tones/daisy.txt b/misc/tones/daisy.txt
new file mode 100644
index 0000000000..e39410621c
--- /dev/null
+++ b/misc/tones/daisy.txt
@@ -0,0 +1 @@
+MFT200O3C4.O2A4.G4.F4.D8E8F8D4F8C2.O2G4.O3C4.O2A4.F4.D8E8F8G4A8G2P8
\ No newline at end of file
diff --git a/misc/tones/dixie.txt b/misc/tones/dixie.txt
new file mode 100644
index 0000000000..f3ddd19ed3
--- /dev/null
+++ b/misc/tones/dixie.txt
@@ -0,0 +1 @@
+MFT60O3C32O2A32F16F16F32G32A32A+32O3C16C16C16O2A16
\ No newline at end of file
diff --git a/misc/tones/tell.txt b/misc/tones/tell.txt
new file mode 100644
index 0000000000..ea77d1a245
--- /dev/null
+++ b/misc/tones/tell.txt
@@ -0,0 +1 @@
+T200O2B4P8B16B16B4P8B16B16B8G+8E8G+8B8G+8B8O3E8O2B8G+8E8G+8B8G+8B8O3E8O2B4P8B16B16B4P8B16O2B16B4P8B16B16B4P8B16B16B8B16B16B8B8B8B16O2B16B8B8B8B16B16B8B8B8B16B16B8B8B2B2B8P8 P4P4P8O1B16B16B8B16B16B8B16B16O2E8F+8G+8 O1B16B16B8B16B16O2E8G+16G+16F+8D+8O1B8B16 O1B16B8B16B16B8B16B16O2E8F+8G+8E16G+16B4 O2B16A16G+16F+16E8G+8E8O3B16B16B8B16B16B8 O3B16B16O4E8F+8G+8O3B16B16B8B16B16O4E8G+16 O4G+16F+8D+8O3B8B16B16B8B16B16B8B16B16O4E8 O4F+8G+8E16G+16B4B16A16G+16F+16E8G+8E8O3G+16 O3G+16G+8G+16G+16G+8G+16G+16G+8O4C+8O3G+8 O4C+8O3G+8O4C+8O3G+8F+8E8D+8C+8G+16G+16G+8 O3G+16G+16G+8G+16G+16G+8O4C+8O3G+8O4C+8O3G+8 O4C+8O3B8A+8B8A+8B8G+16G+16G+8G+16G+16G+8 O3G+16G+16G+8O4C+8O3G+8O4C+8O3G+8O4C+8O3G+8 O3F+8E8D+8C+8G+16G+16G+8G+16G+16G+8G+16G+16 O3G+8O4C+8O3G+8O4C+8O3G+8O4C+8O3B8A+8B8O2B16 O2B16B8F+16F+16F+8F+16F+16F+8G+8A8F+4A8G+8 O2E4G+8F+8F+8F+8O3F+16F+16F+8F+16F+16F+8 O3G+8A8F+4A8G+8E4G+8F+8O2B16B16B8O1B16B16 O1B8B16B16B8B16B16O2E8F+8G+8O1B16B16B8B16 O1B16O2E8G+16G+16F+8D+8O1B8B16B16B8B16B16 O1B8B16B16O2E8F+8G+8E16G+16B4B16A16G+16F+16 O2E8G+8E8O3B16B16B8B16B16B8B16B16O4E8F+8 O4G+8O3B16B16B8B16B16O4E8G+16G+16F+8D+8O3B8 O3B16B16B8B16B16B8B16B16O4E8F+8G+8E16G+16 O4B4B16A16G+16F+16E8G+8E8O3E64F64G64A64B64 O4C64D64E8E16E16E8E8G+4.F+8E8D+8E8C+8O3B16 O4C+16O3B16O4C+16O3B16O4C+16D+16E16O3A16 O3B16A16B16A16B16O4C+16D+16O3G+16A16G+16 O3A16G+16A16B16O4C+16O3F+16G+16F+16G+16F+16 O3G+16F+16G+16F+16G+16F+16D+16O2B16O3B16 O4C+16D+16E8D+8E8C+8O3B16O4C+16O3B16O4C+16 O3B16O4C+16D+16E16O3A16B16A16B16A16B16O4C+16 O4D+16O3G+16A16G+16A16G+16A16B16O4C+16O3F+16 O3G+16F+16G+16F+16A16F+16E16E8P8C+4C+16O2C16 O3C+16O2C16O3D+16C+16O2B16A16A16G+16E16C+16 O2C+16C+16C+16C+16E16D+16O1C16G+16G+16G+16 O1G+16G+16G+16O2C+16E16G+16O3C+16C+16C+16 O3C+16C+16O2C16O3C+16O2C16O3D+16C+16O2B16 O2A16A16G+16E16C+16C+16C+16C+16C+16E16D+16 O1C16G+16G+16G+16G+16G+16G+16O2C+16E16G+16 O3C+16E16D+16C+16D+16O2C16G+16G+16G+16O3G+16 O3E16C+16D+16O2C16G+16G+16G+16O3G+16E16C+16 O3D+16O2B16G+16G+16A+16G16D+16D+16G+16G16 O2G+16G16G+16A16G+16F+16E16O1B16A+16B16O2E16 O1B16O2F+16O1B16O2G+16E16D+16E16G+16E16A16 O2F+16B16O3G+16F+16E16D+16F+16E16C+16O2B16 O3C+16O2B16O3C+16D+16E16F+16G+16O2A16B16 O2A16B16O3C+16D+16E16F+16O2G+16A16G+16A16 O2C16O3C+16D+16E16O2F+16G+16F+16G+16F+16 O2G+16F+16G+16F+16G+16F+16D+16O1B16C16O2C+16 O2D+16E16O1B16A+16B16O2E16O1B16O2F+16O1B16 O2G+16E16D+16E16G+16E16A16F+16B16O3G+16F+16 O3E16D+16F+16E16C+16O2B16O3C+16O2B16O3C+16 O3D+16E16F+16G+16O2A16B16A16B16O3C+16D+16 O3E16F+16O2G+16A16G+16A16B16O3C+16D+16E16 O2F+16O3C+16O2C16O3C+16D+16C+16O2A16F+16 O2E16O3E16F+16G+16A16B16O4C+16D+16E8E16E16 O4E8E8G+4.F8E8D+8E8C+8O3B16O4C+16O3B16O4C+16 O3B16O4C+16D+16E16O3A16B16A16B16A16B16O4C+16 O4D+16O3G+16A16G+16A16G+16A16B16O4C+16O3F+16 O3G+16F+16G+16F+16G+16F+16G+16F+16G+16F+16 O3D+16O2B16O3B16O4C+16D+16E8E16E16E8E8G+4." O4F+8E8D+8E8C+8O3B16O4C+16O3B16O4C+16O3B16 O4C+16D+16E16O3A16B16A16B16A16B16O4C+16D+16 O3G+16A16G+16A16G+16A16B16O4C+16O3F+16G+16 O3F+16G+16F+16A16G+16F+16E8O2B8O3E8G+16G+16 O3G+8G+16G+16G+8G+16G+16G+8O4C+8O3G+8O4C+8 O3G+8O4C+8O3G+8F+8E8D+8C+8G+16G+16G+8G+16 O3G+16G+8G+16G+16G+8O4C+8O3G+8O4C+8O3G+8 O4C+8O3B8A+8B8A+8B8G+16G+16G+8G+16G+16G+8 O3G+16G+16G+8O4C+8O3G+8O4C+8O3G+8O4C+8O3G+8 O3F+8E8D+8C+8G+16G+16G+8G+16G+16G+8G+16G+16 O3G+8O4C+8O3G+8O4C+8O3G+8O4C+8O3B8A+8B8A+8 O3B8O2F+16F+16F+8F+16F+16F+8G+8A8F+4A8G+8 O2E4G+8F+8B8O1B8O2F+16F+16F+8F+16F+16F+8 O2G+8A8F+4A8G+8E4G+8F+8B16B16B8O1B16B16B8 O1B16B16B8B16B16O2E8F+8G+8O1B16B16B8B16B16 O2E8G+16G+16F+8D+8O1B8B16B16B8B16B16B8B16 O1B16O2E8F+8G+8E16G+16B4B16A16G+16F+16E8 O1B8O2E8O3B16B16B8B16B16B8B16B16O4E8F+8G+8 O3B16B16B8B16B16O4E8G+16G+16F+8D+8O3B8B16 O3B16B8B16B16B8B16B16O4E8F+8G+8O3E16G+16 O3B4B16A16G+16F+16E16F+16G+16A16G+16A16B16 O4C+16O3B16O4C+16D+16E16D+16E16F+16G+16A16 O3B16O4A16O3B16O4A16O3B16O4A16O3B16O4A16 O3B16O4A16O3B16O4A16O3B16O4A16O3B16E16F+16 O3G+16A16G+16A16B16O4C+16O3B16O4C+16D+16 O4E16D+16E16F+16G+16A16O3B16O4A16O3B16O4A16 O3B16O4A16O3B16O4A16O3B16O4A16O3B16O4A16 O3B16O4A16O3B16P16G+16O4G+16O3G+16P16D+16 O4D+16O3D+16P16E16O4E16O3E16P16A16O4A16O3A16 P16O3G+16O4G+16O3G+16P16D+16O4D+16O3D+16 P16O3E16O4E16O3E16P16A16O4A16O3A16O4G16O3G16 O4G16O3G16O4G16O3G16O4G16O3G16O4G8E8C8E8 O4G+16O3G+16O4G+16O3G+16O4G+16O3G+16O4G+16 O3G+16O4G+8E8O3B8O4E8G+16O3G+16O4G+16O3G+16 O4G+16O3G+16O4G+16O3G+16O4G+8F8C+8F8A+16 O3A+16O4A+16O3A+16O4A+16O3A+16O4A+16O3A+16 O4A+8G8E8G8B8P16A+16P16A16P16G+16P16F+16 P16O4E16P16D+16P16C+16P16O3B16P16A+16P16 O3A16P16G+16P16F+16P16E16P16D+16P16F+16E16 O3F+16G+16A16G+16A16B16O4C+16O3B16O4C+16 O4D+16E16D+16E16F+16G+16A16O3B16O4A16O3B16 O4A16O3B16O4A16O3B16O4A16O3B16O4A16O3B16 O4A16O3B16O4A16O3B16E16F+16G+16A16G+16A16 O3B16O4C+16O3B16O4C+16D+16E16D+16E16F+16 O4G+16A16O3B16O4A16O3B16O4A16O3B16O4A16O3B16 O4A16O3B16O4A16O3B16O4A16O3B16O4A16O3B16 P16O3G+16O4G+16O3G+16P16D+16O4D+16O3D+16 P16O3E16O4E16O3E16P16A16O4A16O3A16P16G+16 O4G+16O3G+16P16D+16O4D+16O3D+16P16E16O4E16 O3E16P16A16O4A16O3A16O4G16O3G16O4G16O3G16 O4G16O3G16O4G16O3G16O4G8E8C8E8G+16O3G+16 O4G+16O3G+16O4G+16O3G+16O4G+16O3G+16O4G+8 O4E8O3B8O4E8G+16O3G+16O4G+16O3G+16O4G+16 O3G+16O4G+16O3G+16O4G+8F8C+8F8A+16O3A+16 O4A+16O3A+16O4A+16O3A+16O4A+16O3A+16O4A+8 O4G8E8G8B8P16A+16P16A16P16G+16P16F+16P16 O4E16P16D+16P16C+16P16O3B16P16A+16P16A16 P16O3G+16P16F+16P16E16P16D+16P16F16E16D+16 O3E16D+16E8B16B16B8B16B16B8B16B16O4E8F+8 O4G+8O3B16B16B8B16B16B8B16B16O4G+8A8B8P8 O4E8F+8G+8P8O3G+8A8B8P8P2O2B16C16O3C+16D16 O3D+16E16F16F+16G16G+16A16A+16B16C16O4C+16 O4D+16E16D+16F+16D+16E16D+16F+16D+16E16D+16 O4F+16D+16E16D+16F+16D+16E16D+16F+16D+16 O4E16D+16F+16D+16E16D+16F+16D+16E16D+16F+16 O4D+16E8E16O3E16O4E16O3E16O4E16O3E16O4E8 O3B16O2B16O3B16O2B16O3B16O2B16O3B8G+16O2G+16 O3G+16O2G+16O3G+16O2G+16O3G8E16O2E16O3E16 O2E16O3E16O2E16O3E8E16E16E8E8E8O2B16B16B8 O2B8B8G+16G+16G+8G+8G+8E16E16E8E8E8O1B8O2E8 O1B8O2G+8E8B8G+8O3E8O2B8O3E8O2B8O3G+8E8B8 O3G+8O4E4P8E16E16E8E8E8E8E4P8E16E4P8O2E16 O2E2P64
\ No newline at end of file
diff --git a/misc/tones/yankee.txt b/misc/tones/yankee.txt
new file mode 100644
index 0000000000..3677b39c17
--- /dev/null
+++ b/misc/tones/yankee.txt
@@ -0,0 +1 @@
+MNT150L8O2GGABGBADGGABL4GL8F+
\ No newline at end of file
diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h
index 839631b3a2..27ace4b7db 100644
--- a/nuttx-configs/px4fmu-v1/include/board.h
+++ b/nuttx-configs/px4fmu-v1/include/board.h
@@ -156,11 +156,6 @@
#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
-/* High-resolution timer
- */
-#define HRT_TIMER 1 /* use timer1 for the HRT */
-#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
-
/* LED definitions ******************************************************************/
/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
* way. The following definitions are used to access individual LEDs.
@@ -215,33 +210,6 @@
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
-/*
- * PWM
- *
- * Four PWM outputs can be configured on pins otherwise shared with
- * USART2; two can take the flow control pins if they are not being used.
- *
- * Pins:
- *
- * CTS - PA0 - TIM2CH1
- * RTS - PA1 - TIM2CH2
- * TX - PA2 - TIM2CH3
- * RX - PA3 - TIM2CH4
- *
- */
-#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1
-#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1
-#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1
-#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1
-
-/*
- * PPM
- *
- * PPM input is handled by the HRT timer.
- */
-#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
-#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
-
/*
* CAN
*
@@ -273,25 +241,6 @@
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8)
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN9)
-/*
- * I2C busses
- */
-#define PX4_I2C_BUS_ESC 1
-#define PX4_I2C_BUS_ONBOARD 2
-#define PX4_I2C_BUS_EXPANSION 3
-
-/*
- * Devices on the onboard bus.
- *
- * Note that these are unshifted addresses.
- */
-#define PX4_I2C_OBDEV_HMC5883 0x1e
-#define PX4_I2C_OBDEV_MS5611 0x76
-#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
-
-#define PX4_I2C_OBDEV_PX4IO_BL 0x18
-#define PX4_I2C_OBDEV_PX4IO 0x1a
-
/*
* SPI
*
@@ -316,27 +265,6 @@
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2
-/*
- * Use these in place of the spi_dev_e enumeration to
- * select a specific SPI device on SPI1
- */
-#define PX4_SPIDEV_GYRO 1
-#define PX4_SPIDEV_ACCEL 2
-#define PX4_SPIDEV_MPU 3
-
-/*
- * Optional devices on IO's external port
- */
-#define PX4_SPIDEV_ACCEL_MAG 2
-
-/*
- * Tone alarm output
- */
-#define TONE_ALARM_TIMER 3 /* timer 3 */
-#define TONE_ALARM_CHANNEL 3 /* channel 3 */
-#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
-#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
-
/************************************************************************************
* Public Data
************************************************************************************/
diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index 5b91930c91..e43b9c18e8 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -327,7 +327,7 @@ CONFIG_BOARD_LOOPSPERMSEC=16717
CONFIG_DRAM_START=0x20000000
CONFIG_DRAM_SIZE=196608
CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
-CONFIG_ARCH_INTERRUPTSTACK=2048
+CONFIG_ARCH_INTERRUPTSTACK=4096
#
# Boot options
@@ -368,7 +368,7 @@ CONFIG_TASK_NAME_SIZE=24
CONFIG_START_YEAR=1970
CONFIG_START_MONTH=1
CONFIG_START_DAY=1
-# CONFIG_DEV_CONSOLE is not set
+CONFIG_DEV_CONSOLE=y
# CONFIG_MUTEX_TYPES is not set
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_SEM_PREALLOCHOLDERS=0
@@ -406,7 +406,7 @@ CONFIG_MAX_TASKS=32
CONFIG_MAX_TASK_ARGS=10
CONFIG_NPTHREAD_KEYS=4
CONFIG_NFILE_DESCRIPTORS=32
-CONFIG_NFILE_STREAMS=25
+CONFIG_NFILE_STREAMS=8
CONFIG_NAME_MAX=32
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_MQ_MAXMSGSIZE=32
@@ -476,11 +476,11 @@ CONFIG_ARCH_HAVE_USART6=y
CONFIG_MCU_SERIAL=y
CONFIG_STANDARD_SERIAL=y
CONFIG_SERIAL_NPOLLWAITERS=2
-# CONFIG_USART1_SERIAL_CONSOLE is not set
+CONFIG_USART1_SERIAL_CONSOLE=y
# CONFIG_USART2_SERIAL_CONSOLE is not set
# CONFIG_UART5_SERIAL_CONSOLE is not set
# CONFIG_USART6_SERIAL_CONSOLE is not set
-CONFIG_NO_SERIAL_CONSOLE=y
+# CONFIG_NO_SERIAL_CONSOLE is not set
#
# USART1 Configuration
@@ -509,8 +509,8 @@ CONFIG_USART2_OFLOWCONTROL=y
#
# UART5 Configuration
#
-CONFIG_UART5_RXBUFSIZE=32
-CONFIG_UART5_TXBUFSIZE=32
+CONFIG_UART5_RXBUFSIZE=512
+CONFIG_UART5_TXBUFSIZE=512
CONFIG_UART5_BAUD=57600
CONFIG_UART5_BITS=8
CONFIG_UART5_PARITY=0
@@ -551,7 +551,7 @@ CONFIG_USBDEV_MAXPOWER=500
# CONFIG_USBDEV_COMPOSITE is not set
# CONFIG_PL2303 is not set
CONFIG_CDCACM=y
-CONFIG_CDCACM_CONSOLE=y
+CONFIG_CDCACM_CONSOLE=n
CONFIG_CDCACM_EP0MAXPACKET=64
CONFIG_CDCACM_EPINTIN=1
CONFIG_CDCACM_EPINTIN_FSSIZE=64
@@ -565,8 +565,8 @@ CONFIG_CDCACM_EPBULKIN_HSSIZE=512
CONFIG_CDCACM_NWRREQS=4
CONFIG_CDCACM_NRDREQS=4
CONFIG_CDCACM_BULKIN_REQLEN=96
-CONFIG_CDCACM_RXBUFSIZE=256
-CONFIG_CDCACM_TXBUFSIZE=256
+CONFIG_CDCACM_RXBUFSIZE=512
+CONFIG_CDCACM_TXBUFSIZE=512
CONFIG_CDCACM_VENDORID=0x26ac
CONFIG_CDCACM_PRODUCTID=0x0010
CONFIG_CDCACM_VENDORSTR="3D Robotics"
@@ -701,18 +701,18 @@ CONFIG_SCHED_WORKQUEUE=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_WORKPRIORITY=192
CONFIG_SCHED_WORKPERIOD=5000
-CONFIG_SCHED_WORKSTACKSIZE=2048
+CONFIG_SCHED_WORKSTACKSIZE=4000
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKPERIOD=50000
-CONFIG_SCHED_LPWORKSTACKSIZE=2048
+CONFIG_SCHED_LPWORKSTACKSIZE=4000
# CONFIG_LIB_KBDCODEC is not set
# CONFIG_LIB_SLCDCODEC is not set
#
# Basic CXX Support
#
-# CONFIG_C99_BOOL8 is not set
+CONFIG_C99_BOOL8=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
# CONFIG_CXX_NEWLONG is not set
diff --git a/nuttx-configs/px4fmu-v2/include/board.h b/nuttx-configs/px4fmu-v2/include/board.h
new file mode 100755
index 0000000000..507df70a23
--- /dev/null
+++ b/nuttx-configs/px4fmu-v2/include/board.h
@@ -0,0 +1,306 @@
+/************************************************************************************
+ * configs/px4fmu/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include
+#ifndef __ASSEMBLY__
+# include
+#endif
+
+#include
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Clocking *************************************************************************/
+/* The PX4FMUV2 uses a 24MHz crystal connected to the HSE.
+ *
+ * This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c:
+ * System Clock source : PLL (HSE)
+ * SYSCLK(Hz) : 168000000 Determined by PLL configuration
+ * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE)
+ * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE)
+ * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1)
+ * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2)
+ * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL)
+ * PLLM : 24 (STM32_PLLCFG_PLLM)
+ * PLLN : 336 (STM32_PLLCFG_PLLN)
+ * PLLP : 2 (STM32_PLLCFG_PLLP)
+ * PLLQ : 7 (STM32_PLLCFG_PPQ)
+ * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
+ * Flash Latency(WS) : 5
+ * Prefetch Buffer : OFF
+ * Instruction cache : ON
+ * Data cache : ON
+ * Require 48MHz for USB OTG FS, : Enabled
+ * SDIO and RNG clock
+ */
+
+/* HSI - 16 MHz RC factory-trimmed
+ * LSI - 32 KHz RC
+ * HSE - On-board crystal frequency is 24MHz
+ * LSE - not installed
+ */
+
+#define STM32_BOARD_XTAL 24000000ul
+
+#define STM32_HSI_FREQUENCY 16000000ul
+#define STM32_LSI_FREQUENCY 32000
+#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
+//#define STM32_LSE_FREQUENCY 32768
+
+/* Main PLL Configuration.
+ *
+ * PLL source is HSE
+ * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
+ * = (25,000,000 / 25) * 336
+ * = 336,000,000
+ * SYSCLK = PLL_VCO / PLLP
+ * = 336,000,000 / 2 = 168,000,000
+ * USB OTG FS, SDIO and RNG Clock
+ * = PLL_VCO / PLLQ
+ * = 48,000,000
+ */
+
+#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
+#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
+#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
+#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7)
+
+#define STM32_SYSCLK_FREQUENCY 168000000ul
+
+/* AHB clock (HCLK) is SYSCLK (168MHz) */
+
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */
+
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
+
+/* Timers driven from APB1 will be twice PCLK1 */
+
+#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
+
+/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */
+
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
+#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
+
+/* Timers driven from APB2 will be twice PCLK2 */
+
+#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK1_FREQUENCY)
+
+/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
+ * otherwise frequency is 2xAPBx.
+ * Note: TIM1,8 are on APB2, others on APB1
+ */
+
+#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
+#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
+
+/* SDIO dividers. Note that slower clocking is required when DMA is disabled
+ * in order to avoid RX overrun/TX underrun errors due to delayed responses
+ * to service FIFOs in interrupt driven mode. These values have not been
+ * tuned!!!
+ *
+ * HCLK=72MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(178+2)=400 KHz
+ */
+
+#define SDIO_INIT_CLKDIV (178 << SDIO_CLKCR_CLKDIV_SHIFT)
+
+/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(2+2)=18 MHz
+ * DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz
+ */
+
+#ifdef CONFIG_SDIO_DMA
+# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
+#else
+# define SDIO_MMCXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT)
+#endif
+
+/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(1+2)=24 MHz
+ * DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz
+ */
+
+#ifdef CONFIG_SDIO_DMA
+# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT)
+#else
+# define SDIO_SDXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT)
+#endif
+
+/* DMA Channl/Stream Selections *****************************************************/
+/* Stream selections are arbitrary for now but might become important in the future
+ * is we set aside more DMA channels/streams.
+ *
+ * SDIO DMA
+ * Â DMAMAP_SDIO_1 = Channel 4, Stream 3 <- may later be used by SPI DMA
+ * Â DMAMAP_SDIO_2 = Channel 4, Stream 6
+ */
+
+#define DMAMAP_SDIO DMAMAP_SDIO_1
+
+/* Alternate function pin selections ************************************************/
+
+/*
+ * UARTs.
+ */
+#define GPIO_USART1_RX GPIO_USART1_RX_1 /* console in from IO */
+#define GPIO_USART1_TX 0 /* USART1 is RX-only */
+
+#define GPIO_USART2_RX GPIO_USART2_RX_2
+#define GPIO_USART2_TX GPIO_USART2_TX_2
+#define GPIO_USART2_RTS GPIO_USART2_RTS_2
+#define GPIO_USART2_CTS GPIO_USART2_CTS_2
+
+#define GPIO_USART3_RX GPIO_USART3_RX_3
+#define GPIO_USART3_TX GPIO_USART3_TX_3
+#define GPIO_USART2_RTS GPIO_USART2_RTS_2
+#define GPIO_USART2_CTS GPIO_USART2_CTS_2
+
+#define GPIO_UART4_RX GPIO_UART4_RX_1
+#define GPIO_UART4_TX GPIO_UART4_TX_1
+
+#define GPIO_USART6_RX GPIO_USART6_RX_1
+#define GPIO_USART6_TX GPIO_USART6_TX_1
+
+#define GPIO_UART7_RX GPIO_UART7_RX_1
+#define GPIO_UART7_TX GPIO_UART7_TX_1
+
+/* UART8 has no alternate pin config */
+
+/* UART RX DMA configurations */
+#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
+#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
+
+/*
+ * CAN
+ *
+ * CAN1 is routed to the onboard transceiver.
+ * CAN2 is routed to the expansion connector.
+ */
+#define GPIO_CAN1_RX GPIO_CAN1_RX_3
+#define GPIO_CAN1_TX GPIO_CAN1_TX_3
+#define GPIO_CAN2_RX GPIO_CAN2_RX_1
+#define GPIO_CAN2_TX GPIO_CAN2_TX_2
+
+/*
+ * I2C
+ *
+ * The optional _GPIO configurations allow the I2C driver to manually
+ * reset the bus to clear stuck slaves. They match the pin configuration,
+ * but are normally-high GPIOs.
+ */
+#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2
+#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
+#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
+#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
+
+#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
+#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1
+#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
+
+/*
+ * SPI
+ *
+ * There are sensors on SPI1, and SPI2 is connected to the FRAM.
+ */
+#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
+#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
+#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
+
+#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1
+#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1
+#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+EXTERN void stm32_boardinitialize(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx-configs/px4fmu-v2/include/nsh_romfsimg.h b/nuttx-configs/px4fmu-v2/include/nsh_romfsimg.h
new file mode 100644
index 0000000000..15e4e7a8d5
--- /dev/null
+++ b/nuttx-configs/px4fmu-v2/include/nsh_romfsimg.h
@@ -0,0 +1,42 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * nsh_romfsetc.h
+ *
+ * This file is a stub for 'make export' purposes; the actual ROMFS
+ * must be supplied by the library client.
+ */
+
+extern unsigned char romfs_img[];
+extern unsigned int romfs_img_len;
diff --git a/nuttx-configs/px4fmu-v2/nsh/Make.defs b/nuttx-configs/px4fmu-v2/nsh/Make.defs
new file mode 100644
index 0000000000..e70320aaa4
--- /dev/null
+++ b/nuttx-configs/px4fmu-v2/nsh/Make.defs
@@ -0,0 +1,179 @@
+############################################################################
+# configs/px4fmu-v2/nsh/Make.defs
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+include ${TOPDIR}/.config
+include ${TOPDIR}/tools/Config.mk
+
+#
+# We only support building with the ARM bare-metal toolchain from
+# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
+#
+CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
+
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+CC = $(CROSSDEV)gcc
+CXX = $(CROSSDEV)g++
+CPP = $(CROSSDEV)gcc -E
+LD = $(CROSSDEV)ld
+AR = $(CROSSDEV)ar rcs
+NM = $(CROSSDEV)nm
+OBJCOPY = $(CROSSDEV)objcopy
+OBJDUMP = $(CROSSDEV)objdump
+
+MAXOPTIMIZATION = -O3
+ARCHCPUFLAGS = -mcpu=cortex-m4 \
+ -mthumb \
+ -march=armv7e-m \
+ -mfpu=fpv4-sp-d16 \
+ -mfloat-abi=hard
+
+
+# enable precise stack overflow tracking
+INSTRUMENTATIONDEFINES = -finstrument-functions \
+ -ffixed-r10
+
+# pull in *just* libm from the toolchain ... this is grody
+LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
+EXTRA_LIBS += $(LIBM)
+
+# use our linker script
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
+else
+ ifeq ($(PX4_WINTOOL),y)
+ # Windows-native toolchains (MSYS)
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+ else
+ # Linux/Cygwin-native toolchain
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+ endif
+endif
+
+# tool versions
+ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
+ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
+
+# optimisation flags
+ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
+ -fno-strict-aliasing \
+ -fno-strength-reduce \
+ -fomit-frame-pointer \
+ -funsafe-math-optimizations \
+ -fno-builtin-printf \
+ -ffunction-sections \
+ -fdata-sections
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ARCHOPTIMIZATION += -g
+endif
+
+ARCHCFLAGS = -std=gnu99
+ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
+ARCHWARNINGS = -Wall \
+ -Wextra \
+ -Wdouble-promotion \
+ -Wshadow \
+ -Wfloat-equal \
+ -Wframe-larger-than=1024 \
+ -Wpointer-arith \
+ -Wlogical-op \
+ -Wmissing-declarations \
+ -Wpacked \
+ -Wno-unused-parameter
+# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
+# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
+# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
+
+ARCHCWARNINGS = $(ARCHWARNINGS) \
+ -Wbad-function-cast \
+ -Wstrict-prototypes \
+ -Wold-style-declaration \
+ -Wmissing-parameter-type \
+ -Wmissing-prototypes \
+ -Wnested-externs \
+ -Wunsuffixed-float-constants
+ARCHWARNINGSXX = $(ARCHWARNINGS) \
+ -Wno-psabi
+ARCHDEFINES =
+ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
+
+# this seems to be the only way to add linker flags
+EXTRA_LIBS += --warn-common \
+ --gc-sections
+
+CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
+CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
+CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
+CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+NXFLATLDFLAGS1 = -r -d -warn-common
+NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
+LDNXFLATFLAGS = -e main -s 2048
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+
+# produce partially-linked $1 from files in $2
+define PRELINK
+ @echo "PRELINK: $1"
+ $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
+endef
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
+
diff --git a/nuttx-configs/px4fmu-v2/nsh/appconfig b/nuttx-configs/px4fmu-v2/nsh/appconfig
new file mode 100644
index 0000000000..0e18aa8ef1
--- /dev/null
+++ b/nuttx-configs/px4fmu-v2/nsh/appconfig
@@ -0,0 +1,52 @@
+############################################################################
+# configs/px4fmu/nsh/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/nsh
+
+# The NSH application library
+CONFIGURED_APPS += nshlib
+CONFIGURED_APPS += system/readline
+
+ifeq ($(CONFIG_CAN),y)
+#CONFIGURED_APPS += examples/can
+endif
+
+#ifeq ($(CONFIG_USBDEV),y)
+#ifeq ($(CONFIG_CDCACM),y)
+CONFIGURED_APPS += examples/cdcacm
+#endif
+#endif
diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig
new file mode 100644
index 0000000000..372453fb6d
--- /dev/null
+++ b/nuttx-configs/px4fmu-v2/nsh/defconfig
@@ -0,0 +1,1060 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+CONFIG_NUTTX_NEWCONFIG=y
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL is not set
+# CONFIG_HOST_LINUX is not set
+CONFIG_HOST_OSX=y
+# CONFIG_HOST_WINDOWS is not set
+# CONFIG_HOST_OTHER is not set
+
+#
+# Build Configuration
+#
+CONFIG_APPS_DIR="../apps"
+# CONFIG_BUILD_2PASS is not set
+
+#
+# Binary Output Formats
+#
+# CONFIG_RRLOAD_BINARY is not set
+# CONFIG_INTELHEX_BINARY is not set
+# CONFIG_MOTOROLA_SREC is not set
+CONFIG_RAW_BINARY=y
+
+#
+# Customize Header Files
+#
+# CONFIG_ARCH_STDBOOL_H is not set
+CONFIG_ARCH_MATH_H=y
+# CONFIG_ARCH_FLOAT_H is not set
+# CONFIG_ARCH_STDARG_H is not set
+
+#
+# Debug Options
+#
+CONFIG_DEBUG=n
+CONFIG_DEBUG_VERBOSE=n
+
+#
+# Subsystem Debug Options
+#
+# CONFIG_DEBUG_MM is not set
+# CONFIG_DEBUG_SCHED is not set
+# CONFIG_DEBUG_USB is not set
+CONFIG_DEBUG_FS=y
+# CONFIG_DEBUG_LIB is not set
+# CONFIG_DEBUG_BINFMT is not set
+# CONFIG_DEBUG_GRAPHICS is not set
+
+#
+# Driver Debug Options
+#
+# CONFIG_DEBUG_ANALOG is not set
+# CONFIG_DEBUG_I2C is not set
+# CONFIG_DEBUG_SPI is not set
+# CONFIG_DEBUG_SDIO is not set
+# CONFIG_DEBUG_GPIO is not set
+CONFIG_DEBUG_DMA=y
+# CONFIG_DEBUG_WATCHDOG is not set
+# CONFIG_DEBUG_AUDIO is not set
+CONFIG_DEBUG_SYMBOLS=y
+
+#
+# System Type
+#
+# CONFIG_ARCH_8051 is not set
+CONFIG_ARCH_ARM=y
+# CONFIG_ARCH_AVR is not set
+# CONFIG_ARCH_HC is not set
+# CONFIG_ARCH_MIPS is not set
+# CONFIG_ARCH_RGMP is not set
+# CONFIG_ARCH_SH is not set
+# CONFIG_ARCH_SIM is not set
+# CONFIG_ARCH_X86 is not set
+# CONFIG_ARCH_Z16 is not set
+# CONFIG_ARCH_Z80 is not set
+CONFIG_ARCH="arm"
+
+#
+# ARM Options
+#
+# CONFIG_ARCH_CHIP_C5471 is not set
+# CONFIG_ARCH_CHIP_CALYPSO is not set
+# CONFIG_ARCH_CHIP_DM320 is not set
+# CONFIG_ARCH_CHIP_IMX is not set
+# CONFIG_ARCH_CHIP_KINETIS is not set
+# CONFIG_ARCH_CHIP_KL is not set
+# CONFIG_ARCH_CHIP_LM is not set
+# CONFIG_ARCH_CHIP_LPC17XX is not set
+# CONFIG_ARCH_CHIP_LPC214X is not set
+# CONFIG_ARCH_CHIP_LPC2378 is not set
+# CONFIG_ARCH_CHIP_LPC31XX is not set
+# CONFIG_ARCH_CHIP_LPC43XX is not set
+# CONFIG_ARCH_CHIP_NUC1XX is not set
+# CONFIG_ARCH_CHIP_SAM34 is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+CONFIG_ARCH_CORTEXM4=y
+CONFIG_ARCH_FAMILY="armv7-m"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_ARCH_HAVE_CMNVECTOR=y
+CONFIG_ARMV7M_CMNVECTOR=y
+CONFIG_ARCH_HAVE_FPU=y
+CONFIG_ARCH_FPU=y
+CONFIG_ARCH_HAVE_MPU=y
+# CONFIG_ARMV7M_MPU is not set
+# CONFIG_DEBUG_HARDFAULT is not set
+
+#
+# ARMV7M Configuration Options
+#
+# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
+CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y
+CONFIG_ARMV7M_STACKCHECK=y
+CONFIG_SERIAL_TERMIOS=y
+CONFIG_SDIO_DMA=y
+CONFIG_SDIO_DMAPRIO=0x00010000
+# CONFIG_SDIO_WIDTH_D1_ONLY is not set
+
+#
+# STM32 Configuration Options
+#
+# CONFIG_ARCH_CHIP_STM32L151C6 is not set
+# CONFIG_ARCH_CHIP_STM32L151C8 is not set
+# CONFIG_ARCH_CHIP_STM32L151CB is not set
+# CONFIG_ARCH_CHIP_STM32L151R6 is not set
+# CONFIG_ARCH_CHIP_STM32L151R8 is not set
+# CONFIG_ARCH_CHIP_STM32L151RB is not set
+# CONFIG_ARCH_CHIP_STM32L151V6 is not set
+# CONFIG_ARCH_CHIP_STM32L151V8 is not set
+# CONFIG_ARCH_CHIP_STM32L151VB is not set
+# CONFIG_ARCH_CHIP_STM32L152C6 is not set
+# CONFIG_ARCH_CHIP_STM32L152C8 is not set
+# CONFIG_ARCH_CHIP_STM32L152CB is not set
+# CONFIG_ARCH_CHIP_STM32L152R6 is not set
+# CONFIG_ARCH_CHIP_STM32L152R8 is not set
+# CONFIG_ARCH_CHIP_STM32L152RB is not set
+# CONFIG_ARCH_CHIP_STM32L152V6 is not set
+# CONFIG_ARCH_CHIP_STM32L152V8 is not set
+# CONFIG_ARCH_CHIP_STM32L152VB is not set
+# CONFIG_ARCH_CHIP_STM32F100C8 is not set
+# CONFIG_ARCH_CHIP_STM32F100CB is not set
+# CONFIG_ARCH_CHIP_STM32F100R8 is not set
+# CONFIG_ARCH_CHIP_STM32F100RB is not set
+# CONFIG_ARCH_CHIP_STM32F100RC is not set
+# CONFIG_ARCH_CHIP_STM32F100RD is not set
+# CONFIG_ARCH_CHIP_STM32F100RE is not set
+# CONFIG_ARCH_CHIP_STM32F100V8 is not set
+# CONFIG_ARCH_CHIP_STM32F100VB is not set
+# CONFIG_ARCH_CHIP_STM32F100VC is not set
+# CONFIG_ARCH_CHIP_STM32F100VD is not set
+# CONFIG_ARCH_CHIP_STM32F100VE is not set
+# CONFIG_ARCH_CHIP_STM32F103C4 is not set
+# CONFIG_ARCH_CHIP_STM32F103C8 is not set
+# CONFIG_ARCH_CHIP_STM32F103RET6 is not set
+# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
+# CONFIG_ARCH_CHIP_STM32F103VET6 is not set
+# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set
+# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set
+# CONFIG_ARCH_CHIP_STM32F107VC is not set
+# CONFIG_ARCH_CHIP_STM32F207IG is not set
+# CONFIG_ARCH_CHIP_STM32F302CB is not set
+# CONFIG_ARCH_CHIP_STM32F302CC is not set
+# CONFIG_ARCH_CHIP_STM32F302RB is not set
+# CONFIG_ARCH_CHIP_STM32F302RC is not set
+# CONFIG_ARCH_CHIP_STM32F302VB is not set
+# CONFIG_ARCH_CHIP_STM32F302VC is not set
+# CONFIG_ARCH_CHIP_STM32F303CB is not set
+# CONFIG_ARCH_CHIP_STM32F303CC is not set
+# CONFIG_ARCH_CHIP_STM32F303RB is not set
+# CONFIG_ARCH_CHIP_STM32F303RC is not set
+# CONFIG_ARCH_CHIP_STM32F303VB is not set
+# CONFIG_ARCH_CHIP_STM32F303VC is not set
+# CONFIG_ARCH_CHIP_STM32F405RG is not set
+# CONFIG_ARCH_CHIP_STM32F405VG is not set
+# CONFIG_ARCH_CHIP_STM32F405ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407VE is not set
+# CONFIG_ARCH_CHIP_STM32F407VG is not set
+# CONFIG_ARCH_CHIP_STM32F407ZE is not set
+# CONFIG_ARCH_CHIP_STM32F407ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407IE is not set
+# CONFIG_ARCH_CHIP_STM32F407IG is not set
+CONFIG_ARCH_CHIP_STM32F427V=y
+# CONFIG_ARCH_CHIP_STM32F427Z is not set
+# CONFIG_ARCH_CHIP_STM32F427I is not set
+# CONFIG_STM32_STM32L15XX is not set
+# CONFIG_STM32_ENERGYLITE is not set
+# CONFIG_STM32_STM32F10XX is not set
+# CONFIG_STM32_VALUELINE is not set
+# CONFIG_STM32_CONNECTIVITYLINE is not set
+# CONFIG_STM32_PERFORMANCELINE is not set
+# CONFIG_STM32_HIGHDENSITY is not set
+# CONFIG_STM32_MEDIUMDENSITY is not set
+# CONFIG_STM32_LOWDENSITY is not set
+# CONFIG_STM32_STM32F20XX is not set
+# CONFIG_STM32_STM32F30XX is not set
+CONFIG_STM32_STM32F40XX=y
+CONFIG_STM32_STM32F427=y
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+CONFIG_STM32_ADC1=y
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+CONFIG_STM32_BKPSRAM=y
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CAN2 is not set
+CONFIG_STM32_CCMDATARAM=y
+# CONFIG_STM32_CRC is not set
+# CONFIG_STM32_CRYP is not set
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=y
+# CONFIG_STM32_DAC1 is not set
+# CONFIG_STM32_DAC2 is not set
+# CONFIG_STM32_DCMI is not set
+# CONFIG_STM32_ETHMAC is not set
+# CONFIG_STM32_FSMC is not set
+# CONFIG_STM32_HASH is not set
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_I2C2=y
+# CONFIG_STM32_I2C3 is not set
+CONFIG_STM32_OTGFS=y
+# CONFIG_STM32_OTGHS is not set
+CONFIG_STM32_PWR=y
+# CONFIG_STM32_RNG is not set
+CONFIG_STM32_SDIO=y
+CONFIG_STM32_SPI1=y
+CONFIG_STM32_SPI2=y
+# CONFIG_STM32_SPI3 is not set
+# CONFIG_STM32_SPI4 is not set
+# CONFIG_STM32_SPI5 is not set
+# CONFIG_STM32_SPI6 is not set
+CONFIG_STM32_SYSCFG=y
+CONFIG_STM32_TIM1=y
+# CONFIG_STM32_TIM2 is not set
+CONFIG_STM32_TIM3=y
+CONFIG_STM32_TIM4=y
+# CONFIG_STM32_TIM5 is not set
+# CONFIG_STM32_TIM6 is not set
+# CONFIG_STM32_TIM7 is not set
+# CONFIG_STM32_TIM8 is not set
+CONFIG_STM32_TIM9=y
+CONFIG_STM32_TIM10=y
+CONFIG_STM32_TIM11=y
+# CONFIG_STM32_TIM12 is not set
+# CONFIG_STM32_TIM13 is not set
+# CONFIG_STM32_TIM14 is not set
+CONFIG_STM32_USART1=y
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART3=y
+CONFIG_STM32_UART4=y
+# CONFIG_STM32_UART5 is not set
+CONFIG_STM32_USART6=y
+CONFIG_STM32_UART7=y
+CONFIG_STM32_UART8=y
+# CONFIG_STM32_IWDG is not set
+CONFIG_STM32_WWDG=y
+CONFIG_STM32_ADC=y
+CONFIG_STM32_SPI=y
+CONFIG_STM32_I2C=y
+
+#
+# Alternate Pin Mapping
+#
+CONFIG_STM32_FLASH_PREFETCH=y
+# CONFIG_STM32_JTAG_DISABLE is not set
+# CONFIG_STM32_JTAG_FULL_ENABLE is not set
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+CONFIG_STM32_JTAG_SW_ENABLE=y
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+# CONFIG_STM32_FORCEPOWER is not set
+# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
+# CONFIG_STM32_CCMEXCLUDE is not set
+CONFIG_STM32_DMACAPABLE=y
+# CONFIG_STM32_TIM1_PWM is not set
+# CONFIG_STM32_TIM3_PWM is not set
+# CONFIG_STM32_TIM4_PWM is not set
+# CONFIG_STM32_TIM9_PWM is not set
+# CONFIG_STM32_TIM10_PWM is not set
+# CONFIG_STM32_TIM11_PWM is not set
+# CONFIG_STM32_TIM1_ADC is not set
+# CONFIG_STM32_TIM3_ADC is not set
+# CONFIG_STM32_TIM4_ADC is not set
+CONFIG_STM32_USART=y
+
+#
+# U[S]ART Configuration
+#
+# CONFIG_USART1_RS485 is not set
+# CONFIG_USART1_RXDMA is not set
+# CONFIG_USART2_RS485 is not set
+CONFIG_USART2_RXDMA=y
+# CONFIG_USART3_RS485 is not set
+# CONFIG_USART3_RXDMA is not set
+# CONFIG_UART4_RS485 is not set
+# CONFIG_UART4_RXDMA is not set
+# CONFIG_USART6_RS485 is not set
+# CONFIG_USART6_RXDMA is not set
+# CONFIG_UART7_RS485 is not set
+# CONFIG_UART7_RXDMA is not set
+# CONFIG_UART8_RS485 is not set
+# CONFIG_UART8_RXDMA is not set
+CONFIG_SERIAL_DISABLE_REORDERING=y
+CONFIG_STM32_USART_SINGLEWIRE=y
+
+#
+# SPI Configuration
+#
+# CONFIG_STM32_SPI_INTERRUPTS is not set
+# CONFIG_STM32_SPI_DMA is not set
+
+#
+# I2C Configuration
+#
+# CONFIG_STM32_I2C_DYNTIMEO is not set
+CONFIG_STM32_I2CTIMEOSEC=0
+CONFIG_STM32_I2CTIMEOMS=10
+CONFIG_STM32_I2CTIMEOTICKS=500
+# CONFIG_STM32_I2C_DUTY16_9 is not set
+
+#
+# SDIO Configuration
+#
+CONFIG_SDIO_PRI=128
+
+#
+# USB Host Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# External Memory Configuration
+#
+
+#
+# Architecture Options
+#
+# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_VECNOTIRQ is not set
+CONFIG_ARCH_DMA=y
+CONFIG_ARCH_IRQPRIO=y
+# CONFIG_CUSTOM_STACK is not set
+# CONFIG_ADDRENV is not set
+CONFIG_ARCH_HAVE_VFORK=y
+CONFIG_ARCH_STACKDUMP=y
+# CONFIG_ENDIAN_BIG is not set
+# CONFIG_ARCH_HAVE_RAMFUNCS is not set
+CONFIG_ARCH_HAVE_RAMVECTORS=y
+# CONFIG_ARCH_RAMVECTORS is not set
+
+#
+# Board Settings
+#
+CONFIG_BOARD_LOOPSPERMSEC=16717
+# CONFIG_ARCH_CALIBRATION is not set
+CONFIG_DRAM_START=0x20000000
+CONFIG_DRAM_SIZE=262144
+CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
+CONFIG_ARCH_INTERRUPTSTACK=4096
+
+#
+# Boot options
+#
+# CONFIG_BOOT_RUNFROMEXTSRAM is not set
+CONFIG_BOOT_RUNFROMFLASH=y
+# CONFIG_BOOT_RUNFROMISRAM is not set
+# CONFIG_BOOT_RUNFROMSDRAM is not set
+# CONFIG_BOOT_COPYTORAM is not set
+
+#
+# Board Selection
+#
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD=""
+
+#
+# Common Board Options
+#
+CONFIG_NSH_MMCSDMINOR=0
+CONFIG_NSH_MMCSDSLOTNO=0
+
+#
+# Board-Specific Options
+#
+
+#
+# RTOS Features
+#
+# CONFIG_BOARD_INITIALIZE is not set
+CONFIG_MSEC_PER_TICK=1
+CONFIG_RR_INTERVAL=0
+CONFIG_SCHED_INSTRUMENTATION=y
+CONFIG_TASK_NAME_SIZE=24
+# CONFIG_SCHED_HAVE_PARENT is not set
+# CONFIG_JULIAN_TIME is not set
+CONFIG_START_YEAR=1970
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=1
+CONFIG_DEV_CONSOLE=y
+# CONFIG_MUTEX_TYPES is not set
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_SEM_PREALLOCHOLDERS=0
+CONFIG_SEM_NNESTPRIO=8
+# CONFIG_FDCLONE_DISABLE is not set
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SCHED_WAITPID=y
+# CONFIG_SCHED_STARTHOOK is not set
+CONFIG_SCHED_ATEXIT=y
+CONFIG_SCHED_ATEXIT_MAX=1
+# CONFIG_SCHED_ONEXIT is not set
+CONFIG_USER_ENTRYPOINT="nsh_main"
+# CONFIG_DISABLE_OS_API is not set
+
+#
+# Signal Numbers
+#
+CONFIG_SIG_SIGUSR1=1
+CONFIG_SIG_SIGUSR2=2
+CONFIG_SIG_SIGALARM=3
+CONFIG_SIG_SIGCONDTIMEDOUT=16
+CONFIG_SIG_SIGWORK=4
+
+#
+# Sizes of configurable things (0 disables)
+#
+CONFIG_MAX_TASKS=32
+CONFIG_MAX_TASK_ARGS=10
+CONFIG_NPTHREAD_KEYS=4
+CONFIG_NFILE_DESCRIPTORS=32
+CONFIG_NFILE_STREAMS=8
+CONFIG_NAME_MAX=32
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=50
+CONFIG_PREALLOC_TIMERS=50
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=6000
+CONFIG_USERMAIN_STACKSIZE=4096
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_PTHREAD_STACK_DEFAULT=2048
+
+#
+# Device Drivers
+#
+# CONFIG_DISABLE_POLL is not set
+CONFIG_DEV_NULL=y
+# CONFIG_DEV_ZERO is not set
+# CONFIG_LOOP is not set
+# CONFIG_RAMDISK is not set
+# CONFIG_CAN is not set
+# CONFIG_PWM is not set
+CONFIG_I2C=y
+# CONFIG_I2C_SLAVE is not set
+CONFIG_I2C_TRANSFER=y
+# CONFIG_I2C_WRITEREAD is not set
+# CONFIG_I2C_POLLED is not set
+# CONFIG_I2C_TRACE is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+CONFIG_I2C_RESET=y
+CONFIG_SPI=y
+# CONFIG_SPI_OWNBUS is not set
+CONFIG_SPI_EXCHANGE=y
+# CONFIG_SPI_CMDDATA is not set
+# CONFIG_RTC is not set
+CONFIG_WATCHDOG=y
+# CONFIG_ANALOG is not set
+# CONFIG_AUDIO_DEVICES is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+# CONFIG_LCD is not set
+CONFIG_MMCSD=y
+CONFIG_MMCSD_NSLOTS=1
+# CONFIG_MMCSD_READONLY is not set
+CONFIG_MMCSD_MULTIBLOCK_DISABLE=y
+# CONFIG_MMCSD_MMCSUPPORT is not set
+# CONFIG_MMCSD_HAVECARDDETECT is not set
+# CONFIG_MMCSD_SPI is not set
+CONFIG_MMCSD_SDIO=y
+# CONFIG_SDIO_MUXBUS is not set
+# CONFIG_SDIO_BLOCKSETUP is not set
+CONFIG_MTD=y
+
+#
+# MTD Configuration
+#
+# CONFIG_MTD_PARTITION is not set
+# CONFIG_MTD_BYTE_WRITE is not set
+
+#
+# MTD Device Drivers
+#
+# CONFIG_RAMMTD is not set
+# CONFIG_MTD_AT24XX is not set
+# CONFIG_MTD_AT45DB is not set
+# CONFIG_MTD_M25P is not set
+# CONFIG_MTD_SMART is not set
+CONFIG_MTD_RAMTRON=y
+# CONFIG_MTD_SST25 is not set
+# CONFIG_MTD_SST39FV is not set
+# CONFIG_MTD_W25 is not set
+CONFIG_PIPES=y
+# CONFIG_PM is not set
+# CONFIG_POWER is not set
+# CONFIG_SENSORS is not set
+CONFIG_SERIAL=y
+# CONFIG_DEV_LOWCONSOLE is not set
+CONFIG_SERIAL_REMOVABLE=y
+# CONFIG_16550_UART is not set
+CONFIG_ARCH_HAVE_UART4=y
+CONFIG_ARCH_HAVE_UART7=y
+CONFIG_ARCH_HAVE_UART8=y
+CONFIG_ARCH_HAVE_USART1=y
+CONFIG_ARCH_HAVE_USART2=y
+CONFIG_ARCH_HAVE_USART3=y
+CONFIG_ARCH_HAVE_USART6=y
+CONFIG_MCU_SERIAL=y
+CONFIG_STANDARD_SERIAL=y
+CONFIG_SERIAL_NPOLLWAITERS=2
+# CONFIG_SERIAL_TIOCSERGSTRUCT is not set
+# CONFIG_USART1_SERIAL_CONSOLE is not set
+# CONFIG_USART2_SERIAL_CONSOLE is not set
+# CONFIG_USART3_SERIAL_CONSOLE is not set
+# CONFIG_UART4_SERIAL_CONSOLE is not set
+# CONFIG_USART6_SERIAL_CONSOLE is not set
+# CONFIG_UART7_SERIAL_CONSOLE is not set
+CONFIG_UART8_SERIAL_CONSOLE=y
+# CONFIG_NO_SERIAL_CONSOLE is not set
+
+#
+# USART1 Configuration
+#
+CONFIG_USART1_RXBUFSIZE=512
+CONFIG_USART1_TXBUFSIZE=512
+CONFIG_USART1_BAUD=115200
+CONFIG_USART1_BITS=8
+CONFIG_USART1_PARITY=0
+CONFIG_USART1_2STOP=0
+# CONFIG_USART1_IFLOWCONTROL is not set
+# CONFIG_USART1_OFLOWCONTROL is not set
+
+#
+# USART2 Configuration
+#
+CONFIG_USART2_RXBUFSIZE=512
+CONFIG_USART2_TXBUFSIZE=512
+CONFIG_USART2_BAUD=57600
+CONFIG_USART2_BITS=8
+CONFIG_USART2_PARITY=0
+CONFIG_USART2_2STOP=0
+CONFIG_USART2_IFLOWCONTROL=y
+CONFIG_USART2_OFLOWCONTROL=y
+
+#
+# USART3 Configuration
+#
+CONFIG_USART3_RXBUFSIZE=512
+CONFIG_USART3_TXBUFSIZE=512
+CONFIG_USART3_BAUD=57600
+CONFIG_USART3_BITS=8
+CONFIG_USART3_PARITY=0
+CONFIG_USART3_2STOP=0
+CONFIG_USART3_IFLOWCONTROL=y
+CONFIG_USART3_OFLOWCONTROL=y
+
+#
+# UART4 Configuration
+#
+CONFIG_UART4_RXBUFSIZE=128
+CONFIG_UART4_TXBUFSIZE=128
+CONFIG_UART4_BAUD=57600
+CONFIG_UART4_BITS=8
+CONFIG_UART4_PARITY=0
+CONFIG_UART4_2STOP=0
+# CONFIG_UART4_IFLOWCONTROL is not set
+# CONFIG_UART4_OFLOWCONTROL is not set
+
+#
+# USART6 Configuration
+#
+CONFIG_USART6_RXBUFSIZE=256
+CONFIG_USART6_TXBUFSIZE=256
+CONFIG_USART6_BAUD=57600
+CONFIG_USART6_BITS=8
+CONFIG_USART6_PARITY=0
+CONFIG_USART6_2STOP=0
+# CONFIG_USART6_IFLOWCONTROL is not set
+# CONFIG_USART6_OFLOWCONTROL is not set
+
+#
+# UART7 Configuration
+#
+CONFIG_UART7_RXBUFSIZE=512
+CONFIG_UART7_TXBUFSIZE=512
+CONFIG_UART7_BAUD=57600
+CONFIG_UART7_BITS=8
+CONFIG_UART7_PARITY=0
+CONFIG_UART7_2STOP=0
+# CONFIG_UART7_IFLOWCONTROL is not set
+# CONFIG_UART7_OFLOWCONTROL is not set
+
+#
+# UART8 Configuration
+#
+CONFIG_UART8_RXBUFSIZE=512
+CONFIG_UART8_TXBUFSIZE=512
+CONFIG_UART8_BAUD=57600
+CONFIG_UART8_BITS=8
+CONFIG_UART8_PARITY=0
+CONFIG_UART8_2STOP=0
+# CONFIG_UART8_IFLOWCONTROL is not set
+# CONFIG_UART8_OFLOWCONTROL is not set
+CONFIG_SERIAL_IFLOWCONTROL=y
+CONFIG_SERIAL_OFLOWCONTROL=y
+CONFIG_USBDEV=y
+
+#
+# USB Device Controller Driver Options
+#
+# CONFIG_USBDEV_ISOCHRONOUS is not set
+# CONFIG_USBDEV_DUALSPEED is not set
+# CONFIG_USBDEV_SELFPOWERED is not set
+CONFIG_USBDEV_BUSPOWERED=y
+CONFIG_USBDEV_MAXPOWER=500
+# CONFIG_USBDEV_DMA is not set
+# CONFIG_USBDEV_TRACE is not set
+
+#
+# USB Device Class Driver Options
+#
+# CONFIG_USBDEV_COMPOSITE is not set
+# CONFIG_PL2303 is not set
+CONFIG_CDCACM=y
+# CONFIG_CDCACM_CONSOLE is not set
+CONFIG_CDCACM_EP0MAXPACKET=64
+CONFIG_CDCACM_EPINTIN=1
+CONFIG_CDCACM_EPINTIN_FSSIZE=64
+CONFIG_CDCACM_EPINTIN_HSSIZE=64
+CONFIG_CDCACM_EPBULKOUT=3
+CONFIG_CDCACM_EPBULKOUT_FSSIZE=64
+CONFIG_CDCACM_EPBULKOUT_HSSIZE=512
+CONFIG_CDCACM_EPBULKIN=2
+CONFIG_CDCACM_EPBULKIN_FSSIZE=64
+CONFIG_CDCACM_EPBULKIN_HSSIZE=512
+CONFIG_CDCACM_NWRREQS=4
+CONFIG_CDCACM_NRDREQS=4
+CONFIG_CDCACM_BULKIN_REQLEN=96
+CONFIG_CDCACM_RXBUFSIZE=512
+CONFIG_CDCACM_TXBUFSIZE=512
+CONFIG_CDCACM_VENDORID=0x26ac
+CONFIG_CDCACM_PRODUCTID=0x0011
+CONFIG_CDCACM_VENDORSTR="3D Robotics"
+CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v2.x"
+# CONFIG_USBMSC is not set
+# CONFIG_USBHOST is not set
+# CONFIG_WIRELESS is not set
+
+#
+# System Logging Device Options
+#
+
+#
+# System Logging
+#
+# CONFIG_RAMLOG is not set
+
+#
+# Networking Support
+#
+# CONFIG_NET is not set
+
+#
+# File Systems
+#
+
+#
+# File system configuration
+#
+# CONFIG_DISABLE_MOUNTPOINT is not set
+# CONFIG_FS_RAMMAP is not set
+CONFIG_FS_FAT=y
+CONFIG_FAT_LCNAMES=y
+CONFIG_FAT_LFN=y
+CONFIG_FAT_MAXFNAME=32
+CONFIG_FS_FATTIME=y
+CONFIG_FAT_DMAMEMORY=y
+CONFIG_FS_NXFFS=y
+CONFIG_NXFFS_PREALLOCATED=y
+CONFIG_NXFFS_ERASEDSTATE=0xff
+CONFIG_NXFFS_PACKTHRESHOLD=32
+CONFIG_NXFFS_MAXNAMLEN=32
+CONFIG_NXFFS_TAILTHRESHOLD=2048
+CONFIG_FS_ROMFS=y
+# CONFIG_FS_SMARTFS is not set
+CONFIG_FS_BINFS=y
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG_ENABLE is not set
+# CONFIG_SYSLOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_NX is not set
+
+#
+# Memory Management
+#
+# CONFIG_MM_MULTIHEAP is not set
+# CONFIG_MM_SMALL is not set
+CONFIG_MM_REGIONS=2
+CONFIG_GRAN=y
+# CONFIG_GRAN_SINGLE is not set
+# CONFIG_GRAN_INTR is not set
+# CONFIG_DEBUG_GRAN is not set
+
+#
+# Audio Support
+#
+# CONFIG_AUDIO is not set
+
+#
+# Binary Formats
+#
+# CONFIG_BINFMT_DISABLE is not set
+# CONFIG_BINFMT_EXEPATH is not set
+# CONFIG_NXFLAT is not set
+# CONFIG_ELF is not set
+CONFIG_BUILTIN=y
+# CONFIG_PIC is not set
+# CONFIG_SYMTAB_ORDEREDBYNAME is not set
+
+#
+# Library Routines
+#
+
+#
+# Standard C Library Options
+#
+CONFIG_STDIO_BUFFER_SIZE=32
+CONFIG_STDIO_LINEBUFFER=y
+CONFIG_NUNGET_CHARS=2
+CONFIG_LIB_HOMEDIR="/"
+# CONFIG_NOPRINTF_FIELDWIDTH is not set
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_LIB_RAND_ORDER=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
+CONFIG_LIBC_STRERROR=y
+# CONFIG_LIBC_STRERROR_SHORT is not set
+# CONFIG_LIBC_PERROR_STDOUT is not set
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_LIB_SENDFILE_BUFSIZE=512
+# CONFIG_ARCH_ROMGETC is not set
+CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y
+CONFIG_ARCH_MEMCPY=y
+# CONFIG_ARCH_MEMCMP is not set
+# CONFIG_ARCH_MEMMOVE is not set
+# CONFIG_ARCH_MEMSET is not set
+# CONFIG_MEMSET_OPTSPEED is not set
+# CONFIG_ARCH_STRCHR is not set
+# CONFIG_ARCH_STRCMP is not set
+# CONFIG_ARCH_STRCPY is not set
+# CONFIG_ARCH_STRNCPY is not set
+# CONFIG_ARCH_STRLEN is not set
+# CONFIG_ARCH_STRNLEN is not set
+# CONFIG_ARCH_BZERO is not set
+
+#
+# Non-standard Library Support
+#
+CONFIG_SCHED_WORKQUEUE=y
+CONFIG_SCHED_HPWORK=y
+CONFIG_SCHED_WORKPRIORITY=192
+CONFIG_SCHED_WORKPERIOD=5000
+CONFIG_SCHED_WORKSTACKSIZE=4000
+CONFIG_SCHED_LPWORK=y
+CONFIG_SCHED_LPWORKPRIORITY=50
+CONFIG_SCHED_LPWORKPERIOD=50000
+CONFIG_SCHED_LPWORKSTACKSIZE=4000
+# CONFIG_LIB_KBDCODEC is not set
+# CONFIG_LIB_SLCDCODEC is not set
+
+#
+# Basic CXX Support
+#
+CONFIG_C99_BOOL8=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=1024
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+CONFIG_EXAMPLES_CDCACM=y
+# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_CXXTEST is not set
+# CONFIG_EXAMPLES_DHCPD is not set
+# CONFIG_EXAMPLES_ELF is not set
+# CONFIG_EXAMPLES_FTPC is not set
+# CONFIG_EXAMPLES_FTPD is not set
+# CONFIG_EXAMPLES_HELLO is not set
+# CONFIG_EXAMPLES_HELLOXX is not set
+# CONFIG_EXAMPLES_JSON is not set
+# CONFIG_EXAMPLES_HIDKBD is not set
+# CONFIG_EXAMPLES_KEYPADTEST is not set
+# CONFIG_EXAMPLES_IGMP is not set
+# CONFIG_EXAMPLES_LCDRW is not set
+# CONFIG_EXAMPLES_MM is not set
+# CONFIG_EXAMPLES_MODBUS is not set
+CONFIG_EXAMPLES_MOUNT=y
+# CONFIG_EXAMPLES_NRF24L01TERM is not set
+CONFIG_EXAMPLES_NSH=y
+# CONFIG_EXAMPLES_NULL is not set
+# CONFIG_EXAMPLES_NX is not set
+# CONFIG_EXAMPLES_NXCONSOLE is not set
+# CONFIG_EXAMPLES_NXFFS is not set
+# CONFIG_EXAMPLES_NXFLAT is not set
+# CONFIG_EXAMPLES_NXHELLO is not set
+# CONFIG_EXAMPLES_NXIMAGE is not set
+# CONFIG_EXAMPLES_NXLINES is not set
+# CONFIG_EXAMPLES_NXTEXT is not set
+# CONFIG_EXAMPLES_OSTEST is not set
+# CONFIG_EXAMPLES_PASHELLO is not set
+# CONFIG_EXAMPLES_PIPE is not set
+# CONFIG_EXAMPLES_POSIXSPAWN is not set
+# CONFIG_EXAMPLES_QENCODER is not set
+# CONFIG_EXAMPLES_RGMP is not set
+# CONFIG_EXAMPLES_ROMFS is not set
+# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_SLCD is not set
+# CONFIG_EXAMPLES_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART is not set
+# CONFIG_EXAMPLES_TCPECHO is not set
+# CONFIG_EXAMPLES_TELNETD is not set
+# CONFIG_EXAMPLES_THTTPD is not set
+# CONFIG_EXAMPLES_TIFF is not set
+# CONFIG_EXAMPLES_TOUCHSCREEN is not set
+# CONFIG_EXAMPLES_UDP is not set
+# CONFIG_EXAMPLES_UIP is not set
+# CONFIG_EXAMPLES_USBSERIAL is not set
+# CONFIG_EXAMPLES_USBMSC is not set
+# CONFIG_EXAMPLES_USBTERM is not set
+# CONFIG_EXAMPLES_WATCHDOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_TIFF is not set
+
+#
+# Interpreters
+#
+# CONFIG_INTERPRETERS_FICL is not set
+# CONFIG_INTERPRETERS_PCODE is not set
+
+#
+# Network Utilities
+#
+
+#
+# Networking Utilities
+#
+# CONFIG_NETUTILS_CODECS is not set
+# CONFIG_NETUTILS_DHCPC is not set
+# CONFIG_NETUTILS_DHCPD is not set
+# CONFIG_NETUTILS_FTPC is not set
+# CONFIG_NETUTILS_FTPD is not set
+# CONFIG_NETUTILS_JSON is not set
+# CONFIG_NETUTILS_RESOLV is not set
+# CONFIG_NETUTILS_SMTP is not set
+# CONFIG_NETUTILS_TELNETD is not set
+# CONFIG_NETUTILS_TFTPC is not set
+# CONFIG_NETUTILS_THTTPD is not set
+# CONFIG_NETUTILS_UIPLIB is not set
+# CONFIG_NETUTILS_WEBCLIENT is not set
+
+#
+# FreeModBus
+#
+# CONFIG_MODBUS is not set
+
+#
+# NSH Library
+#
+CONFIG_NSH_LIBRARY=y
+CONFIG_NSH_BUILTIN_APPS=y
+
+#
+# Disable Individual commands
+#
+# CONFIG_NSH_DISABLE_CAT is not set
+# CONFIG_NSH_DISABLE_CD is not set
+# CONFIG_NSH_DISABLE_CP is not set
+# CONFIG_NSH_DISABLE_DD is not set
+# CONFIG_NSH_DISABLE_ECHO is not set
+# CONFIG_NSH_DISABLE_EXEC is not set
+# CONFIG_NSH_DISABLE_EXIT is not set
+# CONFIG_NSH_DISABLE_FREE is not set
+# CONFIG_NSH_DISABLE_GET is not set
+# CONFIG_NSH_DISABLE_HELP is not set
+# CONFIG_NSH_DISABLE_HEXDUMP is not set
+# CONFIG_NSH_DISABLE_IFCONFIG is not set
+# CONFIG_NSH_DISABLE_KILL is not set
+# CONFIG_NSH_DISABLE_LOSETUP is not set
+# CONFIG_NSH_DISABLE_LS is not set
+# CONFIG_NSH_DISABLE_MB is not set
+# CONFIG_NSH_DISABLE_MKDIR is not set
+# CONFIG_NSH_DISABLE_MKFATFS is not set
+# CONFIG_NSH_DISABLE_MKFIFO is not set
+# CONFIG_NSH_DISABLE_MKRD is not set
+# CONFIG_NSH_DISABLE_MH is not set
+# CONFIG_NSH_DISABLE_MOUNT is not set
+# CONFIG_NSH_DISABLE_MW is not set
+# CONFIG_NSH_DISABLE_NSFMOUNT is not set
+# CONFIG_NSH_DISABLE_PS is not set
+# CONFIG_NSH_DISABLE_PING is not set
+# CONFIG_NSH_DISABLE_PUT is not set
+# CONFIG_NSH_DISABLE_PWD is not set
+# CONFIG_NSH_DISABLE_RM is not set
+# CONFIG_NSH_DISABLE_RMDIR is not set
+# CONFIG_NSH_DISABLE_SET is not set
+# CONFIG_NSH_DISABLE_SH is not set
+# CONFIG_NSH_DISABLE_SLEEP is not set
+# CONFIG_NSH_DISABLE_TEST is not set
+# CONFIG_NSH_DISABLE_UMOUNT is not set
+# CONFIG_NSH_DISABLE_UNSET is not set
+# CONFIG_NSH_DISABLE_USLEEP is not set
+# CONFIG_NSH_DISABLE_WGET is not set
+# CONFIG_NSH_DISABLE_XD is not set
+
+#
+# Configure Command Options
+#
+# CONFIG_NSH_CMDOPT_DF_H is not set
+CONFIG_NSH_CODECS_BUFSIZE=128
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_STRERROR=y
+CONFIG_NSH_LINELEN=128
+CONFIG_NSH_MAXARGUMENTS=12
+CONFIG_NSH_NESTDEPTH=8
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLEBG is not set
+CONFIG_NSH_ROMFSETC=y
+# CONFIG_NSH_ROMFSRC is not set
+CONFIG_NSH_ROMFSMOUNTPT="/etc"
+CONFIG_NSH_INITSCRIPT="init.d/rcS"
+CONFIG_NSH_ROMFSDEVNO=0
+CONFIG_NSH_ROMFSSECTSIZE=128
+CONFIG_NSH_ARCHROMFS=y
+CONFIG_NSH_FATDEVNO=1
+CONFIG_NSH_FATSECTSIZE=512
+CONFIG_NSH_FATNSECTORS=1024
+CONFIG_NSH_FATMOUNTPT="/tmp"
+CONFIG_NSH_CONSOLE=y
+# CONFIG_NSH_USBCONSOLE is not set
+
+#
+# USB Trace Support
+#
+# CONFIG_NSH_USBDEV_TRACE is not set
+# CONFIG_NSH_CONDEV is not set
+CONFIG_NSH_ARCHINIT=y
+
+#
+# NxWidgets/NxWM
+#
+
+#
+# System NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# I2C tool
+#
+# CONFIG_SYSTEM_I2CTOOL is not set
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+# CONFIG_SYSTEM_FLASH_ERASEALL is not set
+
+#
+# readline()
+#
+CONFIG_SYSTEM_READLINE=y
+CONFIG_READLINE_ECHO=y
+
+#
+# Power Off
+#
+# CONFIG_SYSTEM_POWEROFF is not set
+
+#
+# RAMTRON
+#
+# CONFIG_SYSTEM_RAMTRON is not set
+
+#
+# SD Card
+#
+# CONFIG_SYSTEM_SDCARD is not set
+
+#
+# Sysinfo
+#
+CONFIG_SYSTEM_SYSINFO=y
+
+#
+# USB Monitor
+#
diff --git a/nuttx-configs/px4fmu-v2/nsh/setenv.sh b/nuttx-configs/px4fmu-v2/nsh/setenv.sh
new file mode 100755
index 0000000000..265520997d
--- /dev/null
+++ b/nuttx-configs/px4fmu-v2/nsh/setenv.sh
@@ -0,0 +1,67 @@
+#!/bin/bash
+# configs/stm3240g-eval/nsh/setenv.sh
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+
+if [ "$_" = "$0" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+WD=`pwd`
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+# This the Cygwin path to the location where I installed the RIDE
+# toolchain under windows. You will also have to edit this if you install
+# the RIDE toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
+
+# This the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# This the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx-configs/px4fmu-v2/scripts/ld.script b/nuttx-configs/px4fmu-v2/scripts/ld.script
new file mode 100644
index 0000000000..1be39fb87f
--- /dev/null
+++ b/nuttx-configs/px4fmu-v2/scripts/ld.script
@@ -0,0 +1,150 @@
+/****************************************************************************
+ * configs/px4fmu/common/ld.script
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/* The STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and
+ * 256Kb of SRAM. SRAM is split up into three blocks:
+ *
+ * 1) 112Kb of SRAM beginning at address 0x2000:0000
+ * 2) 16Kb of SRAM beginning at address 0x2001:c000
+ * 3) 64Kb of SRAM beginning at address 0x2002:0000
+ * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x4000 of flash is reserved for the bootloader.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
+ ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
+}
+
+OUTPUT_ARCH(arm)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+
+ /*
+ * This is a hack to make the newlib libm __errno() call
+ * use the NuttX get_errno_ptr() function.
+ */
+ __errno = get_errno_ptr;
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Construction data for parameters.
+ */
+ __param ALIGN(4): {
+ __param_start = ABSOLUTE(.);
+ KEEP(*(__param*))
+ __param_end = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx-configs/px4fmu-v2/src/Makefile b/nuttx-configs/px4fmu-v2/src/Makefile
new file mode 100644
index 0000000000..d4276f7fc5
--- /dev/null
+++ b/nuttx-configs/px4fmu-v2/src/Makefile
@@ -0,0 +1,84 @@
+############################################################################
+# configs/px4fmu/src/Makefile
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = empty.c
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ $(call ARCHIVE, $@, $(OBJS))
+
+.depend: Makefile $(SRCS)
+ $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ $(Q) touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, libboard$(LIBEXT))
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
+
diff --git a/nuttx-configs/px4fmu-v2/src/empty.c b/nuttx-configs/px4fmu-v2/src/empty.c
new file mode 100644
index 0000000000..ace900866c
--- /dev/null
+++ b/nuttx-configs/px4fmu-v2/src/empty.c
@@ -0,0 +1,4 @@
+/*
+ * There are no source files here, but libboard.a can't be empty, so
+ * we have this empty source file to keep it company.
+ */
diff --git a/nuttx-configs/px4io-v1/include/board.h b/nuttx-configs/px4io-v1/include/board.h
index 6503a94cd0..8150792665 100755
--- a/nuttx-configs/px4io-v1/include/board.h
+++ b/nuttx-configs/px4io-v1/include/board.h
@@ -115,22 +115,6 @@
#undef GPIO_USART3_RTS
#define GPIO_USART3_RTS 0xffffffff
-/*
- * High-resolution timer
- */
-#define HRT_TIMER 1 /* use timer1 for the HRT */
-#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
-
-/*
- * PPM
- *
- * PPM input is handled by the HRT timer.
- *
- * Pin is PA8, timer 1, channel 1
- */
-#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
-#define GPIO_PPM_IN GPIO_TIM1_CH1IN
-
/************************************************************************************
* Public Data
************************************************************************************/
diff --git a/nuttx-configs/px4io-v2/include/board.h b/nuttx-configs/px4io-v2/include/board.h
new file mode 100755
index 0000000000..4b9c906385
--- /dev/null
+++ b/nuttx-configs/px4io-v2/include/board.h
@@ -0,0 +1,149 @@
+/************************************************************************************
+ * configs/px4io/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include
+#ifndef __ASSEMBLY__
+# include
+#endif
+#include
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Clocking *************************************************************************/
+
+/* On-board crystal frequency is 24MHz (HSE) */
+
+#define STM32_BOARD_XTAL 24000000ul
+
+/* Use the HSE output as the system clock */
+
+#define STM32_SYSCLK_SW RCC_CFGR_SW_HSE
+#define STM32_SYSCLK_SWS RCC_CFGR_SWS_HSE
+#define STM32_SYSCLK_FREQUENCY STM32_BOARD_XTAL
+
+/* AHB clock (HCLK) is SYSCLK (24MHz) */
+
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB2 clock (PCLK2) is HCLK (24MHz) */
+
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
+#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY
+#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-4 */
+
+/* APB2 timer 1 will receive PCLK2. */
+
+#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
+
+/* APB1 clock (PCLK1) is HCLK (24MHz) */
+
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY)
+
+/* All timers run off PCLK */
+
+#define STM32_APB1_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB1_TIM2_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (STM32_PCLK1_FREQUENCY)
+
+/*
+ * Some of the USART pins are not available; override the GPIO
+ * definitions with an invalid pin configuration.
+ */
+#undef GPIO_USART2_CTS
+#define GPIO_USART2_CTS 0xffffffff
+#undef GPIO_USART2_RTS
+#define GPIO_USART2_RTS 0xffffffff
+#undef GPIO_USART2_CK
+#define GPIO_USART2_CK 0xffffffff
+#undef GPIO_USART3_TX
+#define GPIO_USART3_TX 0xffffffff
+#undef GPIO_USART3_CK
+#define GPIO_USART3_CK 0xffffffff
+#undef GPIO_USART3_CTS
+#define GPIO_USART3_CTS 0xffffffff
+#undef GPIO_USART3_RTS
+#define GPIO_USART3_RTS 0xffffffff
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+EXTERN void stm32_boardinitialize(void);
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx-configs/px4io-v2/nsh/Make.defs b/nuttx-configs/px4io-v2/nsh/Make.defs
new file mode 100644
index 0000000000..cd2d8eba3b
--- /dev/null
+++ b/nuttx-configs/px4io-v2/nsh/Make.defs
@@ -0,0 +1,170 @@
+############################################################################
+# configs/px4io-v2/nsh/Make.defs
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+include ${TOPDIR}/.config
+include ${TOPDIR}/tools/Config.mk
+
+#
+# We only support building with the ARM bare-metal toolchain from
+# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
+#
+CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
+
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+CC = $(CROSSDEV)gcc
+CXX = $(CROSSDEV)g++
+CPP = $(CROSSDEV)gcc -E
+LD = $(CROSSDEV)ld
+AR = $(CROSSDEV)ar rcs
+NM = $(CROSSDEV)nm
+OBJCOPY = $(CROSSDEV)objcopy
+OBJDUMP = $(CROSSDEV)objdump
+
+MAXOPTIMIZATION = -O3
+ARCHCPUFLAGS = -mcpu=cortex-m3 \
+ -mthumb \
+ -march=armv7-m
+
+# enable precise stack overflow tracking
+#INSTRUMENTATIONDEFINES = -finstrument-functions \
+# -ffixed-r10
+
+# use our linker script
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
+else
+ ifeq ($(PX4_WINTOOL),y)
+ # Windows-native toolchains (MSYS)
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+ else
+ # Linux/Cygwin-native toolchain
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+ endif
+endif
+
+# tool versions
+ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
+ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
+
+# optimisation flags
+ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
+ -fno-strict-aliasing \
+ -fno-strength-reduce \
+ -fomit-frame-pointer \
+ -funsafe-math-optimizations \
+ -fno-builtin-printf \
+ -ffunction-sections \
+ -fdata-sections
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ARCHOPTIMIZATION += -g
+endif
+
+ARCHCFLAGS = -std=gnu99
+ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
+ARCHWARNINGS = -Wall \
+ -Wextra \
+ -Wdouble-promotion \
+ -Wshadow \
+ -Wfloat-equal \
+ -Wframe-larger-than=1024 \
+ -Wpointer-arith \
+ -Wlogical-op \
+ -Wmissing-declarations \
+ -Wpacked \
+ -Wno-unused-parameter
+# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
+# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
+# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
+
+ARCHCWARNINGS = $(ARCHWARNINGS) \
+ -Wbad-function-cast \
+ -Wstrict-prototypes \
+ -Wold-style-declaration \
+ -Wmissing-parameter-type \
+ -Wmissing-prototypes \
+ -Wnested-externs \
+ -Wunsuffixed-float-constants
+ARCHWARNINGSXX = $(ARCHWARNINGS)
+ARCHDEFINES =
+ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
+
+# this seems to be the only way to add linker flags
+EXTRA_LIBS += --warn-common \
+ --gc-sections
+
+CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
+CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
+CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
+CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+NXFLATLDFLAGS1 = -r -d -warn-common
+NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
+LDNXFLATFLAGS = -e main -s 2048
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+# produce partially-linked $1 from files in $2
+define PRELINK
+ @echo "PRELINK: $1"
+ $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
+endef
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
+
diff --git a/nuttx-configs/px4io-v2/nsh/appconfig b/nuttx-configs/px4io-v2/nsh/appconfig
new file mode 100644
index 0000000000..48a41bcdb8
--- /dev/null
+++ b/nuttx-configs/px4io-v2/nsh/appconfig
@@ -0,0 +1,32 @@
+############################################################################
+#
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
diff --git a/nuttx-configs/px4io-v2/nsh/defconfig b/nuttx-configs/px4io-v2/nsh/defconfig
new file mode 100755
index 0000000000..4111e70eba
--- /dev/null
+++ b/nuttx-configs/px4io-v2/nsh/defconfig
@@ -0,0 +1,548 @@
+############################################################################
+# configs/px4io/nsh/defconfig
+#
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+#
+# architecture selection
+#
+# CONFIG_ARCH - identifies the arch subdirectory and, hence, the
+# processor architecture.
+# CONFIG_ARCH_family - for use in C code. This identifies the
+# particular chip family that the architecture is implemented
+# in.
+# CONFIG_ARCH_architecture - for use in C code. This identifies the
+# specific architecture within the chip family.
+# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
+# CONFIG_ARCH_CHIP_name - For use in C code
+# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
+# the board that supports the particular chip or SoC.
+# CONFIG_ARCH_BOARD_name - for use in C code
+# CONFIG_ENDIAN_BIG - define if big endian (default is little endian)
+# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
+# CONFIG_DRAM_SIZE - Describes the installed DRAM.
+# CONFIG_DRAM_START - The start address of DRAM (physical)
+# CONFIG_ARCH_IRQPRIO - The ST32F100CB supports interrupt prioritization
+# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
+# stack. If defined, this symbol is the size of the interrupt
+# stack in bytes. If not defined, the user task stacks will be
+# used during interrupt handling.
+# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
+# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
+# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
+# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
+# cause a 100 second delay during boot-up. This 100 second delay
+# serves no purpose other than it allows you to calibrate
+# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
+# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
+# the delay actually is 100 seconds.
+# CONFIG_ARCH_DMA - Support DMA initialization
+#
+CONFIG_ARCH="arm"
+CONFIG_ARCH_ARM=y
+CONFIG_ARCH_CORTEXM3=y
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARCH_CHIP_STM32F100C8=y
+CONFIG_ARCH_BOARD="px4io-v2"
+CONFIG_ARCH_BOARD_PX4IO_V2=y
+CONFIG_BOARD_LOOPSPERMSEC=2000
+CONFIG_DRAM_SIZE=0x00002000
+CONFIG_DRAM_START=0x20000000
+CONFIG_ARCH_IRQPRIO=y
+CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_ARCH_BOOTLOADER=n
+CONFIG_ARCH_LEDS=n
+CONFIG_ARCH_BUTTONS=n
+CONFIG_ARCH_CALIBRATION=n
+CONFIG_ARCH_DMA=y
+CONFIG_ARCH_MATH_H=y
+
+CONFIG_ARMV7M_CMNVECTOR=y
+
+#
+# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
+#
+# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG
+#
+# JTAG Enable options:
+#
+# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+# but without JNTRST.
+# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
+#
+CONFIG_STM32_DFU=n
+CONFIG_STM32_JTAG_FULL_ENABLE=y
+CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
+CONFIG_STM32_JTAG_SW_ENABLE=n
+
+#
+# Individual subsystems can be enabled:
+#
+# AHB:
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=n
+CONFIG_STM32_CRC=n
+# APB1:
+# Timers 2,3 and 4 are owned by the PWM driver
+CONFIG_STM32_TIM2=n
+CONFIG_STM32_TIM3=n
+CONFIG_STM32_TIM4=n
+CONFIG_STM32_TIM5=n
+CONFIG_STM32_TIM6=n
+CONFIG_STM32_TIM7=n
+CONFIG_STM32_WWDG=n
+CONFIG_STM32_SPI2=n
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART3=y
+CONFIG_STM32_I2C1=n
+CONFIG_STM32_I2C2=n
+CONFIG_STM32_BKP=n
+CONFIG_STM32_PWR=n
+CONFIG_STM32_DAC=n
+# APB2:
+# We use our own ADC driver, but leave this on for clocking purposes.
+CONFIG_STM32_ADC1=y
+CONFIG_STM32_ADC2=n
+# TIM1 is owned by the HRT
+CONFIG_STM32_TIM1=n
+CONFIG_STM32_SPI1=n
+CONFIG_STM32_TIM8=n
+CONFIG_STM32_USART1=y
+CONFIG_STM32_ADC3=n
+
+
+#
+# STM32F100 specific serial device driver settings
+#
+# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the
+# console and ttys0 (default is the USART1).
+# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received.
+# This specific the size of the receive buffer
+# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before
+# being sent. This specific the size of the transmit buffer
+# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be
+# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8.
+# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+# CONFIG_USARTn_2STOP - Two stop bits
+#
+CONFIG_SERIAL_TERMIOS=y
+CONFIG_STANDARD_SERIAL=y
+
+CONFIG_USART1_SERIAL_CONSOLE=y
+CONFIG_USART2_SERIAL_CONSOLE=n
+CONFIG_USART3_SERIAL_CONSOLE=n
+
+CONFIG_USART1_TXBUFSIZE=64
+CONFIG_USART2_TXBUFSIZE=64
+CONFIG_USART3_TXBUFSIZE=64
+
+CONFIG_USART1_RXBUFSIZE=64
+CONFIG_USART2_RXBUFSIZE=64
+CONFIG_USART3_RXBUFSIZE=64
+
+CONFIG_USART1_BAUD=115200
+CONFIG_USART2_BAUD=115200
+CONFIG_USART3_BAUD=115200
+
+CONFIG_USART1_BITS=8
+CONFIG_USART2_BITS=8
+CONFIG_USART3_BITS=8
+
+CONFIG_USART1_PARITY=0
+CONFIG_USART2_PARITY=0
+CONFIG_USART3_PARITY=0
+
+CONFIG_USART1_2STOP=0
+CONFIG_USART2_2STOP=0
+CONFIG_USART3_2STOP=0
+
+CONFIG_USART1_RXDMA=y
+SERIAL_HAVE_CONSOLE_DMA=y
+# Conflicts with I2C1 DMA
+CONFIG_USART2_RXDMA=n
+CONFIG_USART3_RXDMA=y
+
+#
+# PX4IO specific driver settings
+#
+# CONFIG_HRT_TIMER
+# Enables the high-resolution timer. The board definition must
+# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/
+# compare channels to be used.
+# CONFIG_HRT_PPM
+# Enables R/C PPM input using the HRT. The board definition must
+# set HRT_PPM_CHANNEL to the timer capture/compare channel to be
+# used, and define GPIO_PPM_IN to configure the appropriate timer
+# GPIO.
+# CONFIG_PWM_SERVO
+# Enables the PWM servo driver. The driver configuration must be
+# supplied by the board support at initialisation time.
+# Note that USART2 must be disabled on the PX4 board for this to
+# be available.
+#
+#
+CONFIG_HRT_TIMER=y
+CONFIG_HRT_PPM=y
+
+#
+# General build options
+#
+# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
+# BSPs from www.ridgerun.com using the tools/mkimage.sh script
+# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format
+# used with many different loaders using the GNU objcopy program
+# Should not be selected if you are not using the GNU toolchain.
+# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format
+# used with many different loaders using the GNU objcopy program
+# Should not be selected if you are not using the GNU toolchain.
+# CONFIG_RAW_BINARY - make a raw binary format file used with many
+# different loaders using the GNU objcopy program. This option
+# should not be selected if you are not using the GNU toolchain.
+# CONFIG_HAVE_LIBM - toolchain supports libm.a
+#
+CONFIG_RRLOAD_BINARY=n
+CONFIG_INTELHEX_BINARY=n
+CONFIG_MOTOROLA_SREC=n
+CONFIG_RAW_BINARY=y
+CONFIG_HAVE_LIBM=n
+
+#
+# General OS setup
+#
+# CONFIG_APPS_DIR - Identifies the relative path to the directory
+# that builds the application to link with NuttX. Default: ../apps
+# CONFIG_DEBUG - enables built-in debug options
+# CONFIG_DEBUG_VERBOSE - enables verbose debug output
+# CONFIG_DEBUG_SYMBOLS - build without optimization and with
+# debug symbols (needed for use with a debugger).
+# CONFIG_HAVE_CXX - Enable support for C++
+# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support
+# for initialization of static C++ instances for this architecture
+# and for the selected toolchain (via up_cxxinitialize()).
+# CONFIG_MM_REGIONS - If the architecture includes multiple
+# regions of memory to allocate from, this specifies the
+# number of memory regions that the memory manager must
+# handle and enables the API mm_addregion(start, end);
+# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot
+# time console output
+# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz
+# or MSEC_PER_TICK=10. This setting may be defined to
+# inform NuttX that the processor hardware is providing
+# system timer interrupts at some interrupt interval other
+# than 10 msec.
+# CONFIG_RR_INTERVAL - The round robin timeslice will be set
+# this number of milliseconds; Round robin scheduling can
+# be disabled by setting this value to zero.
+# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in
+# scheduler to monitor system performance
+# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a
+# task name to save in the TCB. Useful if scheduler
+# instrumentation is selected. Set to zero to disable.
+# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY -
+# Used to initialize the internal time logic.
+# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions.
+# You would only need this if you are concerned about accurate
+# time conversions in the past or in the distant future.
+# CONFIG_JULIAN_TIME - Enables Julian time conversions. You
+# would only need this if you are concerned about accurate
+# time conversion in the distand past. You must also define
+# CONFIG_GREGORIAN_TIME in order to use Julian time.
+# CONFIG_DEV_CONSOLE - Set if architecture-specific logic
+# provides /dev/console. Enables stdout, stderr, stdin.
+# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console
+# driver (minimul support)
+# CONFIG_MUTEX_TYPES: Set to enable support for recursive and
+# errorcheck mutexes. Enables pthread_mutexattr_settype().
+# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority
+# inheritance on mutexes and semaphores.
+# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority
+# inheritance is enabled. It defines the maximum number of
+# different threads (minus one) that can take counts on a
+# semaphore with priority inheritance support. This may be
+# set to zero if priority inheritance is disabled OR if you
+# are only using semaphores as mutexes (only one holder) OR
+# if no more than two threads participate using a counting
+# semaphore.
+# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled,
+# then this setting is the maximum number of higher priority
+# threads (minus 1) than can be waiting for another thread
+# to release a count on a semaphore. This value may be set
+# to zero if no more than one thread is expected to wait for
+# a semaphore.
+# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors
+# by task_create() when a new task is started. If set, all
+# files/drivers will appear to be closed in the new task.
+# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first
+# three file descriptors (stdin, stdout, stderr) by task_create()
+# when a new task is started. If set, all files/drivers will
+# appear to be closed in the new task except for stdin, stdout,
+# and stderr.
+# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket
+# desciptors by task_create() when a new task is started. If
+# set, all sockets will appear to be closed in the new task.
+# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
+# handle delayed processing from interrupt handlers. This feature
+# is required for some drivers but, if there are not complaints,
+# can be safely disabled. The worker thread also performs
+# garbage collection -- completing any delayed memory deallocations
+# from interrupt handlers. If the worker thread is disabled,
+# then that clean will be performed by the IDLE thread instead
+# (which runs at the lowest of priority and may not be appropriate
+# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
+# is enabled, then the following options can also be used:
+# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
+# thread. Default: 50
+# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
+# work in units of microseconds. Default: 50*1000 (50 MS).
+# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
+# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
+# the worker thread. Default: 4
+# CONFIG_SCHED_WAITPID - Enable the waitpid() API
+# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
+#
+CONFIG_USER_ENTRYPOINT="user_start"
+#CONFIG_APPS_DIR=
+CONFIG_DEBUG=n
+CONFIG_DEBUG_VERBOSE=n
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEBUG_FS=n
+CONFIG_DEBUG_GRAPHICS=n
+CONFIG_DEBUG_LCD=n
+CONFIG_DEBUG_USB=n
+CONFIG_DEBUG_NET=n
+CONFIG_DEBUG_RTC=n
+CONFIG_DEBUG_ANALOG=n
+CONFIG_DEBUG_PWM=n
+CONFIG_DEBUG_CAN=n
+CONFIG_DEBUG_I2C=n
+CONFIG_DEBUG_INPUT=n
+
+CONFIG_MSEC_PER_TICK=1
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+CONFIG_MM_REGIONS=1
+CONFIG_MM_SMALL=y
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_RR_INTERVAL=0
+CONFIG_SCHED_INSTRUMENTATION=n
+CONFIG_TASK_NAME_SIZE=8
+CONFIG_START_YEAR=1970
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=1
+CONFIG_GREGORIAN_TIME=n
+CONFIG_JULIAN_TIME=n
+# this eats ~1KiB of RAM ... work out why
+CONFIG_DEV_CONSOLE=y
+CONFIG_DEV_LOWCONSOLE=n
+CONFIG_MUTEX_TYPES=n
+CONFIG_PRIORITY_INHERITANCE=n
+CONFIG_SEM_PREALLOCHOLDERS=0
+CONFIG_SEM_NNESTPRIO=0
+CONFIG_FDCLONE_DISABLE=y
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SCHED_WORKQUEUE=n
+CONFIG_SCHED_WORKPRIORITY=50
+CONFIG_SCHED_WORKPERIOD=50000
+CONFIG_SCHED_WORKSTACKSIZE=1024
+CONFIG_SIG_SIGWORK=4
+CONFIG_SCHED_WAITPID=n
+CONFIG_SCHED_ATEXIT=n
+
+#
+# The following can be used to disable categories of
+# APIs supported by the OS. If the compiler supports
+# weak functions, then it should not be necessary to
+# disable functions unless you want to restrict usage
+# of those APIs.
+#
+# There are certain dependency relationships in these
+# features.
+#
+# o mq_notify logic depends on signals to awaken tasks
+# waiting for queues to become full or empty.
+# o pthread_condtimedwait() depends on signals to wake
+# up waiting tasks.
+#
+CONFIG_DISABLE_CLOCK=n
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_DISABLE_SIGNALS=y
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_ENVIRON=y
+CONFIG_DISABLE_POLL=y
+
+#
+# Misc libc settings
+#
+# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
+# little smaller if we do not support fieldwidthes
+#
+CONFIG_NOPRINTF_FIELDWIDTH=n
+
+#
+# Allow for architecture optimized implementations
+#
+# The architecture can provide optimized versions of the
+# following to improve system performance
+#
+CONFIG_ARCH_MEMCPY=n
+CONFIG_ARCH_MEMCMP=n
+CONFIG_ARCH_MEMMOVE=n
+CONFIG_ARCH_MEMSET=n
+CONFIG_ARCH_STRCMP=n
+CONFIG_ARCH_STRCPY=n
+CONFIG_ARCH_STRNCPY=n
+CONFIG_ARCH_STRLEN=n
+CONFIG_ARCH_STRNLEN=n
+CONFIG_ARCH_BZERO=n
+
+#
+# Sizes of configurable things (0 disables)
+#
+# CONFIG_MAX_TASKS - The maximum number of simultaneously
+# active tasks. This value must be a power of two.
+# CONFIG_MAX_TASK_ARGS - This controls the maximum number of
+# of parameters that a task may receive (i.e., maxmum value
+# of 'argc')
+# CONFIG_NPTHREAD_KEYS - The number of items of thread-
+# specific data that can be retained
+# CONFIG_NFILE_DESCRIPTORS - The maximum number of file
+# descriptors (one for each open)
+# CONFIG_NFILE_STREAMS - The maximum number of streams that
+# can be fopen'ed
+# CONFIG_NAME_MAX - The maximum size of a file name.
+# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
+# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_STDIO_LINEBUFFER - If standard C buffered I/O is enabled
+# (CONFIG_STDIO_BUFFER_SIZE > 0), then this option may be added
+# to force automatic, line-oriented flushing the output buffer
+# for putc(), fputc(), putchar(), puts(), fputs(), printf(),
+# fprintf(), and vfprintf(). When a newline is encountered in
+# the output string, the output buffer will be flushed. This
+# (slightly) increases the NuttX footprint but supports the kind
+# of behavior that people expect for printf().
+# CONFIG_NUNGET_CHARS - Number of characters that can be
+# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
+# structures. The system manages a pool of preallocated
+# message structures to minimize dynamic allocations
+# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with
+# a fixed payload size given by this settin (does not include
+# other message structure overhead.
+# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that
+# can be passed to a watchdog handler
+# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog
+# structures. The system manages a pool of preallocated
+# watchdog structures to minimize dynamic allocations
+# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX
+# timer structures. The system manages a pool of preallocated
+# timer structures to minimize dynamic allocations. Set to
+# zero for all dynamic allocations.
+#
+CONFIG_MAX_TASKS=4
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=2
+CONFIG_NFILE_DESCRIPTORS=8
+CONFIG_NFILE_STREAMS=0
+CONFIG_NAME_MAX=12
+CONFIG_STDIO_BUFFER_SIZE=32
+CONFIG_STDIO_LINEBUFFER=n
+CONFIG_NUNGET_CHARS=2
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_PREALLOC_TIMERS=0
+
+
+#
+# Settings for apps/nshlib
+#
+# CONFIG_NSH_BUILTIN_APPS - Support external registered,
+# "named" applications that can be executed from the NSH
+# command line (see apps/README.txt for more information).
+# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
+# CONFIG_NSH_STRERROR - Use strerror(errno)
+# CONFIG_NSH_LINELEN - Maximum length of one command line
+# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi
+# CONFIG_NSH_DISABLESCRIPT - Disable scripting support
+# CONFIG_NSH_DISABLEBG - Disable background commands
+# CONFIG_NSH_ROMFSETC - Use startup script in /etc
+# CONFIG_NSH_CONSOLE - Use serial console front end
+# CONFIG_NSH_TELNET - Use telnetd console front end
+# CONFIG_NSH_ARCHINIT - Platform provides architecture
+# specific initialization (nsh_archinitialize()).
+#
+
+# Disable NSH completely
+CONFIG_NSH_CONSOLE=n
+
+#
+# Stack and heap information
+#
+# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
+# operation from FLASH but must copy initialized .data sections to RAM.
+# (should also be =n for the STM3210E-EVAL which always runs from flash)
+# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH
+# but copy themselves entirely into RAM for better performance.
+# CONFIG_CUSTOM_STACK - The up_ implementation will handle
+# all stack operations outside of the nuttx model.
+# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only)
+# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack.
+# This is the thread that (1) performs the inital boot of the system up
+# to the point where user_start() is spawned, and (2) there after is the
+# IDLE thread that executes only when there is no other thread ready to
+# run.
+# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate
+# for the main user thread that begins at the user_start() entry point.
+# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
+# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size
+# CONFIG_HEAP_BASE - The beginning of the heap
+# CONFIG_HEAP_SIZE - The size of the heap
+#
+CONFIG_BOOT_RUNFROMFLASH=n
+CONFIG_BOOT_COPYTORAM=n
+CONFIG_CUSTOM_STACK=n
+CONFIG_STACK_POINTER=
+CONFIG_IDLETHREAD_STACKSIZE=1024
+CONFIG_USERMAIN_STACKSIZE=1200
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_PTHREAD_STACK_DEFAULT=1024
+CONFIG_HEAP_BASE=
+CONFIG_HEAP_SIZE=
diff --git a/nuttx-configs/px4io-v2/nsh/setenv.sh b/nuttx-configs/px4io-v2/nsh/setenv.sh
new file mode 100755
index 0000000000..ff9a4bf8ae
--- /dev/null
+++ b/nuttx-configs/px4io-v2/nsh/setenv.sh
@@ -0,0 +1,47 @@
+#!/bin/bash
+# configs/stm3210e-eval/dfu/setenv.sh
+#
+# Copyright (C) 2009 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+
+if [ "$(basename $0)" = "setenv.sh" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
+
+WD=`pwd`
+export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
+export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx-configs/px4io-v2/scripts/ld.script b/nuttx-configs/px4io-v2/scripts/ld.script
new file mode 100755
index 0000000000..69c2f9cb2e
--- /dev/null
+++ b/nuttx-configs/px4io-v2/scripts/ld.script
@@ -0,0 +1,129 @@
+/****************************************************************************
+ * configs/stm3210e-eval/nsh/ld.script
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/* The STM32F100C8 has 64Kb of FLASH beginning at address 0x0800:0000 and
+ * 8Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH,
+ * FLASH memory is aliased to address 0x0000:0000 where the code expects to
+ * begin execution by jumping to the entry point in the 0x0800:0000 address
+ * range.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08001000, LENGTH = 60K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K
+}
+
+OUTPUT_ARCH(arm)
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ /* The STM32F100CB has 8Kb of SRAM beginning at the following address */
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx-configs/px4io-v2/src/Makefile b/nuttx-configs/px4io-v2/src/Makefile
new file mode 100644
index 0000000000..bb9539d16a
--- /dev/null
+++ b/nuttx-configs/px4io-v2/src/Makefile
@@ -0,0 +1,84 @@
+############################################################################
+# configs/stm3210e-eval/src/Makefile
+#
+# Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = empty.c
+
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ $(call ARCHIVE, $@, $(OBJS))
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, libboard$(LIBEXT))
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
diff --git a/nuttx-configs/px4io-v2/src/empty.c b/nuttx-configs/px4io-v2/src/empty.c
new file mode 100644
index 0000000000..ace900866c
--- /dev/null
+++ b/nuttx-configs/px4io-v2/src/empty.c
@@ -0,0 +1,4 @@
+/*
+ * There are no source files here, but libboard.a can't be empty, so
+ * we have this empty source file to keep it company.
+ */
diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp
index 5a8157debc..5e45cc936c 100644
--- a/src/drivers/airspeed/airspeed.cpp
+++ b/src/drivers/airspeed/airspeed.cpp
@@ -68,6 +68,7 @@
#include
#include
+#include
#include
#include
@@ -77,10 +78,9 @@
Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) :
I2C("Airspeed", AIRSPEED_DEVICE_PATH, bus, address, 100000),
- _num_reports(0),
- _next_report(0),
- _oldest_report(0),
_reports(nullptr),
+ _buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows")),
+ _max_differential_pressure_pa(0),
_sensor_ok(false),
_measure_ticks(0),
_collect_phase(false),
@@ -88,8 +88,7 @@ Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) :
_airspeed_pub(-1),
_conversion_interval(conversion_interval),
_sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")),
- _comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors")),
- _buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows"))
+ _comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors"))
{
// enable debug() calls
_debug_enabled = true;
@@ -105,7 +104,12 @@ Airspeed::~Airspeed()
/* free any existing reports */
if (_reports != nullptr)
- delete[] _reports;
+ delete _reports;
+
+ // free perf counters
+ perf_free(_sample_perf);
+ perf_free(_comms_errors);
+ perf_free(_buffer_overflows);
}
int
@@ -118,20 +122,14 @@ Airspeed::init()
goto out;
/* allocate basic report buffers */
- _num_reports = 2;
- _reports = new struct differential_pressure_s[_num_reports];
-
- for (unsigned i = 0; i < _num_reports; i++)
- _reports[i].max_differential_pressure_pa = 0;
-
+ _reports = new RingBuffer(2, sizeof(differential_pressure_s));
if (_reports == nullptr)
goto out;
- _oldest_report = _next_report = 0;
-
/* get a publish handle on the airspeed topic */
- memset(&_reports[0], 0, sizeof(_reports[0]));
- _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_reports[0]);
+ differential_pressure_s zero_report;
+ memset(&zero_report, 0, sizeof(zero_report));
+ _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &zero_report);
if (_airspeed_pub < 0)
warnx("failed to create airspeed sensor object. Did you start uOrb?");
@@ -146,7 +144,14 @@ out:
int
Airspeed::probe()
{
- return measure();
+ /* on initial power up the device needs more than one retry
+ for detection. Once it is running then retries aren't
+ needed
+ */
+ _retries = 4;
+ int ret = measure();
+ _retries = 2;
+ return ret;
}
int
@@ -217,31 +222,22 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
return (1000 / _measure_ticks);
case SENSORIOCSQUEUEDEPTH: {
- /* add one to account for the sentinel in the ring */
- arg++;
-
/* lower bound is mandatory, upper bound is a sanity check */
- if ((arg < 2) || (arg > 100))
+ if ((arg < 1) || (arg > 100))
return -EINVAL;
- /* allocate new buffer */
- struct differential_pressure_s *buf = new struct differential_pressure_s[arg];
-
- if (nullptr == buf)
+ irqstate_t flags = irqsave();
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
return -ENOMEM;
-
- /* reset the measurement state machine with the new buffer, free the old */
- stop();
- delete[] _reports;
- _num_reports = arg;
- _reports = buf;
- start();
+ }
+ irqrestore(flags);
return OK;
}
case SENSORIOCGQUEUEDEPTH:
- return _num_reports - 1;
+ return _reports->size();
case SENSORIOCRESET:
/* XXX implement this */
@@ -269,7 +265,8 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
ssize_t
Airspeed::read(struct file *filp, char *buffer, size_t buflen)
{
- unsigned count = buflen / sizeof(struct differential_pressure_s);
+ unsigned count = buflen / sizeof(differential_pressure_s);
+ differential_pressure_s *abuf = reinterpret_cast(buffer);
int ret = 0;
/* buffer must be large enough */
@@ -285,10 +282,9 @@ Airspeed::read(struct file *filp, char *buffer, size_t buflen)
* we are careful to avoid racing with them.
*/
while (count--) {
- if (_oldest_report != _next_report) {
- memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
- ret += sizeof(_reports[0]);
- INCREMENT(_oldest_report, _num_reports);
+ if (_reports->get(abuf)) {
+ ret += sizeof(*abuf);
+ abuf++;
}
}
@@ -297,9 +293,8 @@ Airspeed::read(struct file *filp, char *buffer, size_t buflen)
}
/* manual measurement - run one conversion */
- /* XXX really it'd be nice to lock against other readers here */
do {
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* trigger a measurement */
if (OK != measure()) {
@@ -317,8 +312,9 @@ Airspeed::read(struct file *filp, char *buffer, size_t buflen)
}
/* state machine will have generated a report, copy it out */
- memcpy(buffer, _reports, sizeof(*_reports));
- ret = sizeof(*_reports);
+ if (_reports->get(abuf)) {
+ ret = sizeof(*abuf);
+ }
} while (0);
@@ -330,7 +326,7 @@ Airspeed::start()
{
/* reset the report ring and state machine */
_collect_phase = false;
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&Airspeed::cycle_trampoline, this, 1);
@@ -373,6 +369,12 @@ Airspeed::print_info()
perf_print_counter(_comms_errors);
perf_print_counter(_buffer_overflows);
warnx("poll interval: %u ticks", _measure_ticks);
- warnx("report queue: %u (%u/%u @ %p)",
- _num_reports, _oldest_report, _next_report, _reports);
+ _reports->print_info("report queue");
+}
+
+void
+Airspeed::new_report(const differential_pressure_s &report)
+{
+ if (!_reports->force(&report))
+ perf_count(_buffer_overflows);
}
diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h
index 89dfb22d70..0487848133 100644
--- a/src/drivers/airspeed/airspeed.h
+++ b/src/drivers/airspeed/airspeed.h
@@ -68,6 +68,7 @@
#include
#include
+#include
#include
#include
@@ -102,6 +103,10 @@ public:
*/
virtual void print_info();
+private:
+ RingBuffer *_reports;
+ perf_counter_t _buffer_overflows;
+
protected:
virtual int probe();
@@ -114,10 +119,7 @@ protected:
virtual int collect() = 0;
work_s _work;
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- differential_pressure_s *_reports;
+ uint16_t _max_differential_pressure_pa;
bool _sensor_ok;
int _measure_ticks;
bool _collect_phase;
@@ -129,7 +131,6 @@ protected:
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
- perf_counter_t _buffer_overflows;
/**
@@ -162,8 +163,12 @@ protected:
*/
static void cycle_trampoline(void *arg);
+ /**
+ * add a new report to the reports queue
+ *
+ * @param report differential_pressure_s report
+ */
+ void new_report(const differential_pressure_s &report);
};
-/* helper macro for handling report buffer indices */
-#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index 735bdb41a5..b88f61ce80 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -53,8 +53,10 @@
#include
#include
#include
-#include
+#include
#include
+#include
+#include
#include
@@ -243,16 +245,14 @@ int ardrone_interface_thread_main(int argc, char *argv[])
int led_counter = 0;
/* declare and safely initialize all structs */
- struct vehicle_status_s state;
- memset(&state, 0, sizeof(state));
struct actuator_controls_s actuator_controls;
memset(&actuator_controls, 0, sizeof(actuator_controls));
struct actuator_armed_s armed;
+ //XXX is this necessairy?
armed.armed = false;
/* subscribe to attitude, motor setpoints and system state */
int actuator_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
- int state_sub = orb_subscribe(ORB_ID(vehicle_status));
int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
printf("[ardrone_interface] Motors initialized - ready.\n");
@@ -322,8 +322,6 @@ int ardrone_interface_thread_main(int argc, char *argv[])
} else {
/* MAIN OPERATION MODE */
- /* get a local copy of the vehicle state */
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
/* get a local copy of the actuator controls */
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_controls_sub, &actuator_controls);
orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
diff --git a/src/drivers/ardrone_interface/ardrone_motor_control.c b/src/drivers/ardrone_interface/ardrone_motor_control.c
index be8968a4ea..01b89c8fa5 100644
--- a/src/drivers/ardrone_interface/ardrone_motor_control.c
+++ b/src/drivers/ardrone_interface/ardrone_motor_control.c
@@ -41,6 +41,7 @@
#include
#include
#include
+#include
#include
#include
#include
@@ -369,11 +370,9 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
float yaw_control = actuators->control[2];
float motor_thrust = actuators->control[3];
- //printf("AMO: Roll: %4.4f, Pitch: %4.4f, Yaw: %4.4f, Thrust: %4.4f\n",roll_control, pitch_control, yaw_control, motor_thrust);
-
const float min_thrust = 0.02f; /**< 2% minimum thrust */
const float max_thrust = 1.0f; /**< 100% max thrust */
- const float scaling = 500.0f; /**< 100% thrust equals a value of 500 which works, 512 leads to cutoff */
+ const float scaling = 510.0f; /**< 100% thrust equals a value of 510 which works, 512 leads to cutoff */
const float min_gas = min_thrust * scaling; /**< value range sent to motors, minimum */
const float max_gas = max_thrust * scaling; /**< value range sent to motors, maximum */
@@ -382,71 +381,56 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
float motor_calc[4] = {0};
float output_band = 0.0f;
- float band_factor = 0.75f;
const float startpoint_full_control = 0.25f; /**< start full control at 25% thrust */
- float yaw_factor = 1.0f;
static bool initialized = false;
/* publish effective outputs */
static struct actuator_controls_effective_s actuator_controls_effective;
static orb_advert_t actuator_controls_effective_pub;
- if (motor_thrust <= min_thrust) {
- motor_thrust = min_thrust;
- output_band = 0.0f;
- } else if (motor_thrust < startpoint_full_control && motor_thrust > min_thrust) {
- output_band = band_factor * (motor_thrust - min_thrust);
- } else if (motor_thrust >= startpoint_full_control && motor_thrust < max_thrust - band_factor * startpoint_full_control) {
- output_band = band_factor * startpoint_full_control;
- } else if (motor_thrust >= max_thrust - band_factor * startpoint_full_control) {
- output_band = band_factor * (max_thrust - motor_thrust);
+ /* linearly scale the control inputs from 0 to startpoint_full_control */
+ if (motor_thrust < startpoint_full_control) {
+ output_band = motor_thrust/startpoint_full_control; // linear from 0 to 1
+ } else {
+ output_band = 1.0f;
}
+ roll_control *= output_band;
+ pitch_control *= output_band;
+ yaw_control *= output_band;
+
+
//add the yaw, nick and roll components to the basic thrust //TODO:this should be done by the mixer
// FRONT (MOTOR 1)
motor_calc[0] = motor_thrust + (roll_control / 2 + pitch_control / 2 - yaw_control);
-
// RIGHT (MOTOR 2)
motor_calc[1] = motor_thrust + (-roll_control / 2 + pitch_control / 2 + yaw_control);
-
// BACK (MOTOR 3)
motor_calc[2] = motor_thrust + (-roll_control / 2 - pitch_control / 2 - yaw_control);
-
// LEFT (MOTOR 4)
motor_calc[3] = motor_thrust + (roll_control / 2 - pitch_control / 2 + yaw_control);
- // if we are not in the output band
- if (!(motor_calc[0] < motor_thrust + output_band && motor_calc[0] > motor_thrust - output_band
- && motor_calc[1] < motor_thrust + output_band && motor_calc[1] > motor_thrust - output_band
- && motor_calc[2] < motor_thrust + output_band && motor_calc[2] > motor_thrust - output_band
- && motor_calc[3] < motor_thrust + output_band && motor_calc[3] > motor_thrust - output_band)) {
+ /* if one motor is saturated, reduce throttle */
+ float saturation = fmaxf(fmaxf(motor_calc[0], motor_calc[1]),fmaxf(motor_calc[2], motor_calc[3])) - max_thrust;
+
+
+ if (saturation > 0.0f) {
+
+ /* reduce the motor thrust according to the saturation */
+ motor_thrust = motor_thrust - saturation;
- yaw_factor = 0.5f;
- yaw_control *= yaw_factor;
// FRONT (MOTOR 1)
motor_calc[0] = motor_thrust + (roll_control / 2 + pitch_control / 2 - yaw_control);
-
// RIGHT (MOTOR 2)
motor_calc[1] = motor_thrust + (-roll_control / 2 + pitch_control / 2 + yaw_control);
-
// BACK (MOTOR 3)
motor_calc[2] = motor_thrust + (-roll_control / 2 - pitch_control / 2 - yaw_control);
-
// LEFT (MOTOR 4)
motor_calc[3] = motor_thrust + (roll_control / 2 - pitch_control / 2 + yaw_control);
}
- for (int i = 0; i < 4; i++) {
- //check for limits
- if (motor_calc[i] < motor_thrust - output_band) {
- motor_calc[i] = motor_thrust - output_band;
- }
- if (motor_calc[i] > motor_thrust + output_band) {
- motor_calc[i] = motor_thrust + output_band;
- }
- }
/* publish effective outputs */
actuator_controls_effective.control_effective[0] = roll_control;
@@ -467,25 +451,29 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
/* set the motor values */
- /* scale up from 0..1 to 10..512) */
+ /* scale up from 0..1 to 10..500) */
motor_pwm[0] = (uint16_t) (motor_calc[0] * ((float)max_gas - min_gas) + min_gas);
motor_pwm[1] = (uint16_t) (motor_calc[1] * ((float)max_gas - min_gas) + min_gas);
motor_pwm[2] = (uint16_t) (motor_calc[2] * ((float)max_gas - min_gas) + min_gas);
motor_pwm[3] = (uint16_t) (motor_calc[3] * ((float)max_gas - min_gas) + min_gas);
- /* Keep motors spinning while armed and prevent overflows */
+ /* scale up from 0..1 to 10..500) */
+ motor_pwm[0] = (uint16_t) (motor_calc[0] * (float)((max_gas - min_gas) + min_gas));
+ motor_pwm[1] = (uint16_t) (motor_calc[1] * (float)((max_gas - min_gas) + min_gas));
+ motor_pwm[2] = (uint16_t) (motor_calc[2] * (float)((max_gas - min_gas) + min_gas));
+ motor_pwm[3] = (uint16_t) (motor_calc[3] * (float)((max_gas - min_gas) + min_gas));
- /* Failsafe logic - should never be necessary */
- motor_pwm[0] = (motor_pwm[0] > 0) ? motor_pwm[0] : 10;
- motor_pwm[1] = (motor_pwm[1] > 0) ? motor_pwm[1] : 10;
- motor_pwm[2] = (motor_pwm[2] > 0) ? motor_pwm[2] : 10;
- motor_pwm[3] = (motor_pwm[3] > 0) ? motor_pwm[3] : 10;
+ /* Failsafe logic for min values - should never be necessary */
+ motor_pwm[0] = (motor_pwm[0] > 0) ? motor_pwm[0] : min_gas;
+ motor_pwm[1] = (motor_pwm[1] > 0) ? motor_pwm[1] : min_gas;
+ motor_pwm[2] = (motor_pwm[2] > 0) ? motor_pwm[2] : min_gas;
+ motor_pwm[3] = (motor_pwm[3] > 0) ? motor_pwm[3] : min_gas;
- /* Failsafe logic - should never be necessary */
- motor_pwm[0] = (motor_pwm[0] <= 511) ? motor_pwm[0] : 511;
- motor_pwm[1] = (motor_pwm[1] <= 511) ? motor_pwm[1] : 511;
- motor_pwm[2] = (motor_pwm[2] <= 511) ? motor_pwm[2] : 511;
- motor_pwm[3] = (motor_pwm[3] <= 511) ? motor_pwm[3] : 511;
+ /* Failsafe logic for max values - should never be necessary */
+ motor_pwm[0] = (motor_pwm[0] <= max_gas) ? motor_pwm[0] : max_gas;
+ motor_pwm[1] = (motor_pwm[1] <= max_gas) ? motor_pwm[1] : max_gas;
+ motor_pwm[2] = (motor_pwm[2] <= max_gas) ? motor_pwm[2] : max_gas;
+ motor_pwm[3] = (motor_pwm[3] <= max_gas) ? motor_pwm[3] : max_gas;
/* send motors via UART */
ardrone_write_motor_commands(ardrone_write, motor_pwm[0], motor_pwm[1], motor_pwm[2], motor_pwm[3]);
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 3fabfd9a54..2361f4dd18 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -92,9 +92,6 @@
#include
-#include
-#include
-
#include
#include
#include
@@ -104,18 +101,23 @@
#include
#include
#include
-
-#include
+#include
#include
#include
#include
-
#include
-#include
+
+#include
+
+#include
+#include
+
#include
#include
+#include
+#include
#include
static const float MAX_CELL_VOLTAGE = 4.3f;
@@ -375,7 +377,9 @@ BlinkM::led()
{
static int vehicle_status_sub_fd;
+ static int vehicle_control_mode_sub_fd;
static int vehicle_gps_position_sub_fd;
+ static int actuator_armed_sub_fd;
static int num_of_cells = 0;
static int detected_cells_runcount = 0;
@@ -386,6 +390,8 @@ BlinkM::led()
static int led_interval = 1000;
static int no_data_vehicle_status = 0;
+ static int no_data_vehicle_control_mode = 0;
+ static int no_data_actuator_armed = 0;
static int no_data_vehicle_gps_position = 0;
static bool topic_initialized = false;
@@ -398,6 +404,12 @@ BlinkM::led()
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
orb_set_interval(vehicle_status_sub_fd, 1000);
+ vehicle_control_mode_sub_fd = orb_subscribe(ORB_ID(vehicle_control_mode));
+ orb_set_interval(vehicle_control_mode_sub_fd, 1000);
+
+ actuator_armed_sub_fd = orb_subscribe(ORB_ID(actuator_armed));
+ orb_set_interval(actuator_armed_sub_fd, 1000);
+
vehicle_gps_position_sub_fd = orb_subscribe(ORB_ID(vehicle_gps_position));
orb_set_interval(vehicle_gps_position_sub_fd, 1000);
@@ -452,12 +464,16 @@ BlinkM::led()
if (led_thread_runcount == 15) {
/* obtained data for the first file descriptor */
struct vehicle_status_s vehicle_status_raw;
+ struct vehicle_control_mode_s vehicle_control_mode;
+ struct actuator_armed_s actuator_armed;
struct vehicle_gps_position_s vehicle_gps_position_raw;
memset(&vehicle_status_raw, 0, sizeof(vehicle_status_raw));
memset(&vehicle_gps_position_raw, 0, sizeof(vehicle_gps_position_raw));
bool new_data_vehicle_status;
+ bool new_data_vehicle_control_mode;
+ bool new_data_actuator_armed;
bool new_data_vehicle_gps_position;
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
@@ -471,6 +487,28 @@ BlinkM::led()
no_data_vehicle_status = 3;
}
+ orb_check(vehicle_control_mode_sub_fd, &new_data_vehicle_control_mode);
+
+ if (new_data_vehicle_control_mode) {
+ orb_copy(ORB_ID(vehicle_control_mode), vehicle_control_mode_sub_fd, &vehicle_control_mode);
+ no_data_vehicle_control_mode = 0;
+ } else {
+ no_data_vehicle_control_mode++;
+ if(no_data_vehicle_control_mode >= 3)
+ no_data_vehicle_control_mode = 3;
+ }
+
+ orb_check(actuator_armed_sub_fd, &new_data_actuator_armed);
+
+ if (new_data_actuator_armed) {
+ orb_copy(ORB_ID(actuator_armed), actuator_armed_sub_fd, &actuator_armed);
+ no_data_actuator_armed = 0;
+ } else {
+ no_data_actuator_armed++;
+ if(no_data_actuator_armed >= 3)
+ no_data_actuator_armed = 3;
+ }
+
orb_check(vehicle_gps_position_sub_fd, &new_data_vehicle_gps_position);
if (new_data_vehicle_gps_position) {
@@ -486,24 +524,24 @@ BlinkM::led()
/* get number of used satellites in navigation */
num_of_used_sats = 0;
- //for(int satloop=0; satloop<20; satloop++) {
- for(int satloop=0; satloop checking cells\n");
for(num_of_cells = 2; num_of_cells < 7; num_of_cells++) {
- if(vehicle_status_raw.voltage_battery < num_of_cells * MAX_CELL_VOLTAGE) break;
+ if(vehicle_status_raw.battery_voltage < num_of_cells * MAX_CELL_VOLTAGE) break;
}
printf(" cells found:%d\n", num_of_cells);
} else {
- if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_WARNING) {
+ if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
/* LED Pattern for battery low warning */
led_color_1 = LED_YELLOW;
led_color_2 = LED_YELLOW;
@@ -515,7 +553,7 @@ BlinkM::led()
led_color_8 = LED_YELLOW;
led_blink = LED_BLINK;
- } else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_ALERT) {
+ } else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) {
/* LED Pattern for battery critical alerting */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
@@ -530,7 +568,7 @@ BlinkM::led()
} else {
/* no battery warnings here */
- if(vehicle_status_raw.flag_system_armed == false) {
+ if(actuator_armed.armed == false) {
/* system not armed */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
@@ -554,27 +592,24 @@ BlinkM::led()
led_color_8 = LED_OFF;
led_blink = LED_BLINK;
- /* handle 4th led - flightmode indicator */
- switch((int)vehicle_status_raw.flight_mode) {
- case VEHICLE_FLIGHT_MODE_MANUAL:
- led_color_4 = LED_AMBER;
- break;
+ if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
- case VEHICLE_FLIGHT_MODE_STAB:
- led_color_4 = LED_YELLOW;
- break;
-
- case VEHICLE_FLIGHT_MODE_HOLD:
- led_color_4 = LED_BLUE;
- break;
-
- case VEHICLE_FLIGHT_MODE_AUTO:
+ //XXX please check
+ if (vehicle_control_mode.flag_control_position_enabled)
led_color_4 = LED_GREEN;
- break;
+ else if (vehicle_control_mode.flag_control_velocity_enabled)
+ led_color_4 = LED_BLUE;
+ else if (vehicle_control_mode.flag_control_attitude_enabled)
+ led_color_4 = LED_YELLOW;
+ else if (vehicle_control_mode.flag_control_manual_enabled)
+ led_color_4 = LED_AMBER;
+ else
+ led_color_4 = LED_OFF;
+
}
if(new_data_vehicle_gps_position || no_data_vehicle_gps_position < 3) {
- /* handling used sat´s */
+ /* handling used sat�s */
if(num_of_used_sats >= 7) {
led_color_1 = LED_OFF;
led_color_2 = LED_OFF;
@@ -831,11 +866,13 @@ BlinkM::get_firmware_version(uint8_t version[2])
return transfer(&msg, sizeof(msg), version, 2);
}
+void blinkm_usage();
+
void blinkm_usage() {
- fprintf(stderr, "missing command: try 'start', 'systemstate', 'ledoff', 'list' or a script name {options}\n");
- fprintf(stderr, "options:\n");
- fprintf(stderr, "\t-b --bus i2cbus (3)\n");
- fprintf(stderr, "\t-a --blinkmaddr blinkmaddr (9)\n");
+ warnx("missing command: try 'start', 'systemstate', 'ledoff', 'list' or a script name {options}");
+ warnx("options:");
+ warnx("\t-b --bus i2cbus (3)");
+ warnx("\t-a --blinkmaddr blinkmaddr (9)");
}
int
diff --git a/src/drivers/bma180/bma180.cpp b/src/drivers/bma180/bma180.cpp
index 4409a8a9cb..1590cc182b 100644
--- a/src/drivers/bma180/bma180.cpp
+++ b/src/drivers/bma180/bma180.cpp
@@ -59,10 +59,11 @@
#include
#include
-#include
+#include
#include
#include
+#include
/* oddly, ERROR is not defined for c++ */
@@ -146,10 +147,7 @@ private:
struct hrt_call _call;
unsigned _call_interval;
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- struct accel_report *_reports;
+ RingBuffer *_reports;
struct accel_scale _accel_scale;
float _accel_range_scale;
@@ -233,16 +231,9 @@ private:
int set_lowpass(unsigned frequency);
};
-/* helper macro for handling report buffer indices */
-#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
-
-
BMA180::BMA180(int bus, spi_dev_e device) :
SPI("BMA180", ACCEL_DEVICE_PATH, bus, device, SPIDEV_MODE3, 8000000),
_call_interval(0),
- _num_reports(0),
- _next_report(0),
- _oldest_report(0),
_reports(nullptr),
_accel_range_scale(0.0f),
_accel_range_m_s2(0.0f),
@@ -270,7 +261,7 @@ BMA180::~BMA180()
/* free any existing reports */
if (_reports != nullptr)
- delete[] _reports;
+ delete _reports;
/* delete the perf counter */
perf_free(_sample_perf);
@@ -286,16 +277,15 @@ BMA180::init()
goto out;
/* allocate basic report buffers */
- _num_reports = 2;
- _oldest_report = _next_report = 0;
- _reports = new struct accel_report[_num_reports];
+ _reports = new RingBuffer(2, sizeof(accel_report));
if (_reports == nullptr)
goto out;
/* advertise sensor topic */
- memset(&_reports[0], 0, sizeof(_reports[0]));
- _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_reports[0]);
+ struct accel_report zero_report;
+ memset(&zero_report, 0, sizeof(zero_report));
+ _accel_topic = orb_advertise(ORB_ID(sensor_accel), &zero_report);
/* perform soft reset (p48) */
write_reg(ADDR_RESET, SOFT_RESET);
@@ -352,6 +342,7 @@ ssize_t
BMA180::read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct accel_report);
+ struct accel_report *arp = reinterpret_cast(buffer);
int ret = 0;
/* buffer must be large enough */
@@ -367,10 +358,9 @@ BMA180::read(struct file *filp, char *buffer, size_t buflen)
* we are careful to avoid racing with it.
*/
while (count--) {
- if (_oldest_report != _next_report) {
- memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
- ret += sizeof(_reports[0]);
- INCREMENT(_oldest_report, _num_reports);
+ if (_reports->get(arp)) {
+ ret += sizeof(*arp);
+ arp++;
}
}
@@ -379,12 +369,12 @@ BMA180::read(struct file *filp, char *buffer, size_t buflen)
}
/* manual measurement */
- _oldest_report = _next_report = 0;
+ _reports->flush();
measure();
/* measurement will have generated a report, copy it out */
- memcpy(buffer, _reports, sizeof(*_reports));
- ret = sizeof(*_reports);
+ if (_reports->get(arp))
+ ret = sizeof(*arp);
return ret;
}
@@ -449,31 +439,22 @@ BMA180::ioctl(struct file *filp, int cmd, unsigned long arg)
return 1000000 / _call_interval;
case SENSORIOCSQUEUEDEPTH: {
- /* account for sentinel in the ring */
- arg++;
-
- /* lower bound is mandatory, upper bound is a sanity check */
- if ((arg < 2) || (arg > 100))
- return -EINVAL;
-
- /* allocate new buffer */
- struct accel_report *buf = new struct accel_report[arg];
-
- if (nullptr == buf)
- return -ENOMEM;
-
- /* reset the measurement state machine with the new buffer, free the old */
- stop();
- delete[] _reports;
- _num_reports = arg;
- _reports = buf;
- start();
-
- return OK;
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 2) || (arg > 100))
+ return -EINVAL;
+
+ irqstate_t flags = irqsave();
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
}
+ irqrestore(flags);
+
+ return OK;
+ }
case SENSORIOCGQUEUEDEPTH:
- return _num_reports - 1;
+ return _reports->size();
case SENSORIOCRESET:
/* XXX implement */
@@ -654,7 +635,7 @@ BMA180::start()
stop();
/* reset the report ring */
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* start polling at the specified rate */
hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&BMA180::measure_trampoline, this);
@@ -688,7 +669,7 @@ BMA180::measure()
// } raw_report;
// #pragma pack(pop)
- accel_report *report = &_reports[_next_report];
+ struct accel_report report;
/* start the performance counter */
perf_begin(_sample_perf);
@@ -708,45 +689,41 @@ BMA180::measure()
* them before. There is no good way to synchronise with the internal
* measurement flow without using the external interrupt.
*/
- _reports[_next_report].timestamp = hrt_absolute_time();
+ report.timestamp = hrt_absolute_time();
+ report.error_count = 0;
/*
* y of board is x of sensor and x of board is -y of sensor
* perform only the axis assignment here.
* Two non-value bits are discarded directly
*/
- report->y_raw = read_reg(ADDR_ACC_X_LSB + 0);
- report->y_raw |= read_reg(ADDR_ACC_X_LSB + 1) << 8;
- report->x_raw = read_reg(ADDR_ACC_X_LSB + 2);
- report->x_raw |= read_reg(ADDR_ACC_X_LSB + 3) << 8;
- report->z_raw = read_reg(ADDR_ACC_X_LSB + 4);
- report->z_raw |= read_reg(ADDR_ACC_X_LSB + 5) << 8;
+ report.y_raw = read_reg(ADDR_ACC_X_LSB + 0);
+ report.y_raw |= read_reg(ADDR_ACC_X_LSB + 1) << 8;
+ report.x_raw = read_reg(ADDR_ACC_X_LSB + 2);
+ report.x_raw |= read_reg(ADDR_ACC_X_LSB + 3) << 8;
+ report.z_raw = read_reg(ADDR_ACC_X_LSB + 4);
+ report.z_raw |= read_reg(ADDR_ACC_X_LSB + 5) << 8;
/* discard two non-value bits in the 16 bit measurement */
- report->x_raw = (report->x_raw / 4);
- report->y_raw = (report->y_raw / 4);
- report->z_raw = (report->z_raw / 4);
+ report.x_raw = (report.x_raw / 4);
+ report.y_raw = (report.y_raw / 4);
+ report.z_raw = (report.z_raw / 4);
/* invert y axis, due to 14 bit data no overflow can occur in the negation */
- report->y_raw = -report->y_raw;
+ report.y_raw = -report.y_raw;
- report->x = ((report->x_raw * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
- report->y = ((report->y_raw * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
- report->z = ((report->z_raw * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
- report->scaling = _accel_range_scale;
- report->range_m_s2 = _accel_range_m_s2;
+ report.x = ((report.x_raw * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
+ report.y = ((report.y_raw * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
+ report.z = ((report.z_raw * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
+ report.scaling = _accel_range_scale;
+ report.range_m_s2 = _accel_range_m_s2;
- /* post a report to the ring - note, not locked */
- INCREMENT(_next_report, _num_reports);
-
- /* if we are running up against the oldest report, fix it */
- if (_next_report == _oldest_report)
- INCREMENT(_oldest_report, _num_reports);
+ _reports->force(&report);
/* notify anyone waiting for data */
poll_notify(POLLIN);
/* publish for subscribers */
- orb_publish(ORB_ID(sensor_accel), _accel_topic, report);
+ orb_publish(ORB_ID(sensor_accel), _accel_topic, &report);
/* stop the perf counter */
perf_end(_sample_perf);
@@ -756,8 +733,7 @@ void
BMA180::print_info()
{
perf_print_counter(_sample_perf);
- printf("report queue: %u (%u/%u @ %p)\n",
- _num_reports, _oldest_report, _next_report, _reports);
+ _reports->print_info("report queue");
}
/**
diff --git a/src/drivers/boards/px4fmu/px4fmu_internal.h b/src/drivers/boards/px4fmu-v1/board_config.h
similarity index 77%
rename from src/drivers/boards/px4fmu/px4fmu_internal.h
rename to src/drivers/boards/px4fmu-v1/board_config.h
index 383a046ffd..27621211a1 100644
--- a/src/drivers/boards/px4fmu/px4fmu_internal.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file px4fmu_internal.h
+ * @file board_config.h
*
* PX4FMU internal definitions
*/
@@ -51,13 +51,16 @@ __BEGIN_DECLS
/* these headers are not C++ safe */
#include
-
+#include
/****************************************************************************************************
* Definitions
****************************************************************************************************/
/* Configuration ************************************************************************************/
+/* PX4IO connection configuration */
+#define PX4IO_SERIAL_DEVICE "/dev/ttyS2"
+
//#ifdef CONFIG_STM32_SPI2
//# error "SPI2 is not supported on this board"
//#endif
@@ -74,15 +77,47 @@ __BEGIN_DECLS
/* External interrupts */
#define GPIO_EXTI_COMPASS (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
-// XXX MPU6000 DRDY?
/* SPI chip selects */
-
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
#define GPIO_SPI_CS_ACCEL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
+/*
+ * Use these in place of the spi_dev_e enumeration to
+ * select a specific SPI device on SPI1
+ */
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_ACCEL 2
+#define PX4_SPIDEV_MPU 3
+
+/*
+ * Optional devices on IO's external port
+ */
+#define PX4_SPIDEV_ACCEL_MAG 2
+
+/*
+ * I2C busses
+ */
+#define PX4_I2C_BUS_ESC 1
+#define PX4_I2C_BUS_ONBOARD 2
+#define PX4_I2C_BUS_EXPANSION 3
+#define PX4_I2C_BUS_LED 3
+
+/*
+ * Devices on the onboard bus.
+ *
+ * Note that these are unshifted addresses.
+ */
+#define PX4_I2C_OBDEV_HMC5883 0x1e
+#define PX4_I2C_OBDEV_MS5611 0x76
+#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
+#define PX4_I2C_OBDEV_LED 0x55
+
+#define PX4_I2C_OBDEV_PX4IO_BL 0x18
+#define PX4_I2C_OBDEV_PX4IO 0x1a
+
/* User GPIOs
*
* GPIO0-1 are the buffered high-power GPIOs.
@@ -107,31 +142,45 @@ __BEGIN_DECLS
#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
#define GPIO_GPIO_DIR (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
+/*
+ * Tone alarm output
+ */
+#define TONE_ALARM_TIMER 3 /* timer 3 */
+#define TONE_ALARM_CHANNEL 3 /* channel 3 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
+
+/*
+ * PWM
+ *
+ * Four PWM outputs can be configured on pins otherwise shared with
+ * USART2; two can take the flow control pins if they are not being used.
+ *
+ * Pins:
+ *
+ * CTS - PA0 - TIM2CH1
+ * RTS - PA1 - TIM2CH2
+ * TX - PA2 - TIM2CH3
+ * RX - PA3 - TIM2CH4
+ *
+ */
+#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1
+#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1
+#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1
+#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1
+
/* USB OTG FS
*
* PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
*/
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
-/* PWM
- *
- * The PX4FMU has five PWM outputs, of which only the output on
- * pin PC8 is fixed assigned to this function. The other four possible
- * pwm sources are the TX, RX, RTS and CTS pins of USART2
- *
- * Alternate function mapping:
- * PC8 - BUZZER - TIM8_CH3/SDIO_D0 /TIM3_CH3/ USART6_CK / DCMI_D2
+/* High-resolution timer
*/
-
-#ifdef CONFIG_PWM
-# if defined(CONFIG_STM32_TIM3_PWM)
-# define BUZZER_PWMCHANNEL 3
-# define BUZZER_PWMTIMER 3
-# elif defined(CONFIG_STM32_TIM8_PWM)
-# define BUZZER_PWMCHANNEL 3
-# define BUZZER_PWMTIMER 8
-# endif
-#endif
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
+#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
/****************************************************************************************************
* Public Types
diff --git a/src/drivers/boards/px4fmu/module.mk b/src/drivers/boards/px4fmu-v1/module.mk
similarity index 100%
rename from src/drivers/boards/px4fmu/module.mk
rename to src/drivers/boards/px4fmu-v1/module.mk
diff --git a/src/drivers/boards/px4fmu/px4fmu_can.c b/src/drivers/boards/px4fmu-v1/px4fmu_can.c
similarity index 99%
rename from src/drivers/boards/px4fmu/px4fmu_can.c
rename to src/drivers/boards/px4fmu-v1/px4fmu_can.c
index 187689ff9a..1e1f100406 100644
--- a/src/drivers/boards/px4fmu/px4fmu_can.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_can.c
@@ -54,7 +54,7 @@
#include "stm32.h"
#include "stm32_can.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
#ifdef CONFIG_CAN
diff --git a/src/drivers/boards/px4fmu/px4fmu_init.c b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
similarity index 98%
rename from src/drivers/boards/px4fmu/px4fmu_init.c
rename to src/drivers/boards/px4fmu-v1/px4fmu_init.c
index 36af2298c2..4b12b75f9e 100644
--- a/src/drivers/boards/px4fmu/px4fmu_init.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
@@ -59,7 +59,7 @@
#include
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
#include "stm32_uart.h"
#include
@@ -222,14 +222,9 @@ __EXPORT int nsh_archinitialize(void)
* If SPI2 is enabled in the defconfig, we loose some ADC pins as chip selects.
* Keep the SPI2 init optional and conditionally initialize the ADC pins
*/
- spi2 = up_spiinitialize(2);
- if (!spi2) {
- message("[boot] Enabling IN12/13 instead of SPI2\n");
- /* no SPI2, use pins for ADC */
- stm32_configgpio(GPIO_ADC1_IN12);
- stm32_configgpio(GPIO_ADC1_IN13); // jumperable to MPU6000 DRDY on some boards
- } else {
+ #ifdef CONFIG_STM32_SPI2
+ spi2 = up_spiinitialize(2);
/* Default SPI2 to 1MHz and de-assert the known chip selects. */
SPI_SETFREQUENCY(spi2, 10000000);
SPI_SETBITS(spi2, 8);
@@ -238,7 +233,13 @@ __EXPORT int nsh_archinitialize(void)
SPI_SELECT(spi2, PX4_SPIDEV_ACCEL_MAG, false);
message("[boot] Initialized SPI port2 (ADC IN12/13 blocked)\n");
- }
+ #else
+ spi2 = NULL;
+ message("[boot] Enabling IN12/13 instead of SPI2\n");
+ /* no SPI2, use pins for ADC */
+ stm32_configgpio(GPIO_ADC1_IN12);
+ stm32_configgpio(GPIO_ADC1_IN13); // jumperable to MPU6000 DRDY on some boards
+ #endif
/* Get the SPI port for the microSD slot */
diff --git a/src/drivers/boards/px4fmu/px4fmu_led.c b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
similarity index 88%
rename from src/drivers/boards/px4fmu/px4fmu_led.c
rename to src/drivers/boards/px4fmu-v1/px4fmu_led.c
index 31b25984e1..ea91f34ad6 100644
--- a/src/drivers/boards/px4fmu/px4fmu_led.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
@@ -42,7 +42,7 @@
#include
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
#include
@@ -57,6 +57,7 @@ __BEGIN_DECLS
extern void led_init();
extern void led_on(int led);
extern void led_off(int led);
+extern void led_toggle(int led);
__END_DECLS
__EXPORT void led_init()
@@ -94,3 +95,21 @@ __EXPORT void led_off(int led)
stm32_gpiowrite(GPIO_LED2, true);
}
}
+
+__EXPORT void led_toggle(int led)
+{
+ if (led == 0)
+ {
+ if (stm32_gpioread(GPIO_LED1))
+ stm32_gpiowrite(GPIO_LED1, false);
+ else
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+ if (led == 1)
+ {
+ if (stm32_gpioread(GPIO_LED2))
+ stm32_gpiowrite(GPIO_LED2, false);
+ else
+ stm32_gpiowrite(GPIO_LED2, true);
+ }
+}
diff --git a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmu-v1/px4fmu_pwm_servo.c
similarity index 98%
rename from src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
rename to src/drivers/boards/px4fmu-v1/px4fmu_pwm_servo.c
index d85131dd88..848e21d798 100644
--- a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_pwm_servo.c
@@ -41,15 +41,15 @@
#include
-#include
-
-#include
-#include
-
#include
#include
#include
+#include
+#include
+
+#include "board_config.h"
+
__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
{
.base = STM32_TIM2_BASE,
diff --git a/src/drivers/boards/px4fmu/px4fmu_spi.c b/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
similarity index 99%
rename from src/drivers/boards/px4fmu/px4fmu_spi.c
rename to src/drivers/boards/px4fmu-v1/px4fmu_spi.c
index e05ddecf3e..17e6862f7c 100644
--- a/src/drivers/boards/px4fmu/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
@@ -53,7 +53,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
/************************************************************************************
* Public Functions
diff --git a/src/drivers/boards/px4fmu/px4fmu_usb.c b/src/drivers/boards/px4fmu-v1/px4fmu_usb.c
similarity index 99%
rename from src/drivers/boards/px4fmu/px4fmu_usb.c
rename to src/drivers/boards/px4fmu-v1/px4fmu_usb.c
index 0be981c1e1..0fc8569aa4 100644
--- a/src/drivers/boards/px4fmu/px4fmu_usb.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_usb.c
@@ -53,7 +53,7 @@
#include "up_arch.h"
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
/************************************************************************************
* Definitions
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
new file mode 100644
index 0000000000..ec8dde4993
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -0,0 +1,192 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file board_config.h
+ *
+ * PX4FMU internal definitions
+ */
+
+#pragma once
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include
+#include
+#include
+
+__BEGIN_DECLS
+
+/* these headers are not C++ safe */
+#include
+#include
+
+/****************************************************************************************************
+ * Definitions
+ ****************************************************************************************************/
+/* Configuration ************************************************************************************/
+
+/* PX4IO connection configuration */
+#define PX4IO_SERIAL_DEVICE "/dev/ttyS4"
+#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
+#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
+#define PX4IO_SERIAL_BASE STM32_USART6_BASE /* hardwired on the board */
+#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
+#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX_2
+#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX_2
+#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
+#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
+
+
+/* PX4FMU GPIOs ***********************************************************************************/
+/* LEDs */
+
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12)
+
+/* External interrupts */
+#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN4)
+
+/* SPI chip selects */
+#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
+#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
+#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
+#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
+
+/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_ACCEL_MAG 2
+#define PX4_SPIDEV_BARO 3
+
+/* I2C busses */
+#define PX4_I2C_BUS_EXPANSION 1
+#define PX4_I2C_BUS_LED 2
+
+/* Devices on the onboard bus.
+ *
+ * Note that these are unshifted addresses.
+ */
+#define PX4_I2C_OBDEV_LED 0x55
+#define PX4_I2C_OBDEV_HMC5883 0x1e
+
+/* User GPIOs
+ *
+ * GPIO0-5 are the PWM servo outputs.
+ */
+#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN14)
+#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN13)
+#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
+#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN9)
+#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
+#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14)
+#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13)
+#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11)
+#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9)
+#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
+
+/* Power supply control and monitoring GPIOs */
+#define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
+#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_VDD_SERVO_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN7)
+#define GPIO_VDD_3V3_SENSORS_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
+#define GPIO_VDD_5V_HIPOWER_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN10)
+#define GPIO_VDD_5V_PERIPH_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15)
+
+/* Tone alarm output */
+#define TONE_ALARM_TIMER 2 /* timer 2 */
+#define TONE_ALARM_CHANNEL 1 /* channel 1 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15)
+
+/* PWM
+ *
+ * Six PWM outputs are configured.
+ *
+ * Pins:
+ *
+ * CH1 : PE14 : TIM1_CH4
+ * CH2 : PE13 : TIM1_CH3
+ * CH3 : PE11 : TIM1_CH2
+ * CH4 : PE9 : TIM1_CH1
+ * CH5 : PD13 : TIM4_CH2
+ * CH6 : PD14 : TIM4_CH3
+ */
+#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2
+#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_2
+#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_2
+#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_2
+#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2
+#define GPIO_TIM4_CH3OUT GPIO_TIM4_CH3OUT_2
+
+/* USB OTG FS
+ *
+ * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
+ */
+#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
+
+/* High-resolution timer */
+#define HRT_TIMER 8 /* use timer8 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public data
+ ****************************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************************
+ * Public Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ****************************************************************************************************/
+
+extern void stm32_spiinitialize(void);
+
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v2/module.mk b/src/drivers/boards/px4fmu-v2/module.mk
new file mode 100644
index 0000000000..99d37eecac
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/module.mk
@@ -0,0 +1,10 @@
+#
+# Board-specific startup code for the PX4FMUv2
+#
+
+SRCS = px4fmu_can.c \
+ px4fmu2_init.c \
+ px4fmu_pwm_servo.c \
+ px4fmu_spi.c \
+ px4fmu_usb.c \
+ px4fmu2_led.c
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
new file mode 100644
index 0000000000..ae2a645f70
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
@@ -0,0 +1,328 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4fmu_init.c
+ *
+ * PX4FMU-specific early startup code. This file implements the
+ * nsh_archinitialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialisation.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include
+
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include "board_config.h"
+#include
+
+#include
+
+#include
+#include
+
+#include
+#include
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+#if defined(CONFIG_FAT_DMAMEMORY)
+# if !defined(CONFIG_GRAN) || !defined(CONFIG_FAT_DMAMEMORY)
+# error microSD DMA support requires CONFIG_GRAN
+# endif
+
+static GRAN_HANDLE dma_allocator;
+
+/*
+ * The DMA heap size constrains the total number of things that can be
+ * ready to do DMA at a time.
+ *
+ * For example, FAT DMA depends on one sector-sized buffer per filesystem plus
+ * one sector-sized buffer per file.
+ *
+ * We use a fundamental alignment / granule size of 64B; this is sufficient
+ * to guarantee alignment for the largest STM32 DMA burst (16 beats x 32bits).
+ */
+static uint8_t g_dma_heap[8192] __attribute__((aligned(64)));
+static perf_counter_t g_dma_perf;
+
+static void
+dma_alloc_init(void)
+{
+ dma_allocator = gran_initialize(g_dma_heap,
+ sizeof(g_dma_heap),
+ 7, /* 128B granule - must be > alignment (XXX bug?) */
+ 6); /* 64B alignment */
+ if (dma_allocator == NULL) {
+ message("[boot] DMA allocator setup FAILED");
+ } else {
+ g_dma_perf = perf_alloc(PC_COUNT, "DMA allocations");
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/*
+ * DMA-aware allocator stubs for the FAT filesystem.
+ */
+
+__EXPORT void *fat_dma_alloc(size_t size);
+__EXPORT void fat_dma_free(FAR void *memory, size_t size);
+
+void *
+fat_dma_alloc(size_t size)
+{
+ perf_count(g_dma_perf);
+ return gran_alloc(dma_allocator, size);
+}
+
+void
+fat_dma_free(FAR void *memory, size_t size)
+{
+ gran_free(dma_allocator, memory, size);
+}
+
+#else
+
+# define dma_alloc_init()
+
+#endif
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void
+stm32_boardinitialize(void)
+{
+ /* configure SPI interfaces */
+ stm32_spiinitialize();
+
+ /* configure LEDs */
+ up_ledinit();
+}
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+static struct spi_dev_s *spi1;
+static struct spi_dev_s *spi2;
+static struct sdio_dev_s *sdio;
+
+#include
+
+#ifdef __cplusplus
+__EXPORT int matherr(struct __exception *e)
+{
+ return 1;
+}
+#else
+__EXPORT int matherr(struct exception *e)
+{
+ return 1;
+}
+#endif
+
+__EXPORT int nsh_archinitialize(void)
+{
+
+ /* configure ADC pins */
+ stm32_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */
+ stm32_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */
+ stm32_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */
+ stm32_configgpio(GPIO_ADC1_IN10); /* unrouted */
+ stm32_configgpio(GPIO_ADC1_IN11); /* unrouted */
+ stm32_configgpio(GPIO_ADC1_IN12); /* unrouted */
+ stm32_configgpio(GPIO_ADC1_IN13); /* FMU_AUX_ADC_1 */
+ stm32_configgpio(GPIO_ADC1_IN14); /* FMU_AUX_ADC_2 */
+ stm32_configgpio(GPIO_ADC1_IN15); /* PRESSURE_SENS */
+
+ /* configure power supply control/sense pins */
+ stm32_configgpio(GPIO_VDD_5V_PERIPH_EN);
+ stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
+ stm32_configgpio(GPIO_VDD_BRICK_VALID);
+ stm32_configgpio(GPIO_VDD_SERVO_VALID);
+ stm32_configgpio(GPIO_VDD_5V_HIPOWER_OC);
+ stm32_configgpio(GPIO_VDD_5V_PERIPH_OC);
+
+ /* configure the high-resolution time/callout interface */
+ hrt_init();
+
+ /* configure the DMA allocator */
+ dma_alloc_init();
+
+ /* configure CPU load estimation */
+#ifdef CONFIG_SCHED_INSTRUMENTATION
+ cpuload_initialize_once();
+#endif
+
+ /* set up the serial DMA polling */
+ static struct hrt_call serial_dma_call;
+ struct timespec ts;
+
+ /*
+ * Poll at 1ms intervals for received bytes that have not triggered
+ * a DMA event.
+ */
+ ts.tv_sec = 0;
+ ts.tv_nsec = 1000000;
+
+ hrt_call_every(&serial_dma_call,
+ ts_to_abstime(&ts),
+ ts_to_abstime(&ts),
+ (hrt_callout)stm32_serial_dma_poll,
+ NULL);
+
+ /* initial LED state */
+ drv_led_start();
+ led_off(LED_AMBER);
+
+ /* Configure SPI-based devices */
+
+ spi1 = up_spiinitialize(1);
+
+ if (!spi1) {
+ message("[boot] FAILED to initialize SPI port 1\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* Default SPI1 to 1MHz and de-assert the known chip selects. */
+ SPI_SETFREQUENCY(spi1, 10000000);
+ SPI_SETBITS(spi1, 8);
+ SPI_SETMODE(spi1, SPIDEV_MODE3);
+ SPI_SELECT(spi1, PX4_SPIDEV_GYRO, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_ACCEL_MAG, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_BARO, false);
+ up_udelay(20);
+
+ message("[boot] Successfully initialized SPI port 1\n");
+
+ /* Get the SPI port for the FRAM */
+
+ spi2 = up_spiinitialize(2);
+
+ if (!spi2) {
+ message("[boot] FAILED to initialize SPI port 2\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* Default SPI2 to 37.5 MHz (F4 max) and de-assert the known chip selects. */
+ SPI_SETFREQUENCY(spi2, 375000000);
+ SPI_SETBITS(spi2, 8);
+ SPI_SETMODE(spi2, SPIDEV_MODE3);
+ SPI_SELECT(spi2, SPIDEV_FLASH, false);
+
+ message("[boot] Successfully initialized SPI port 2\n");
+
+ #ifdef CONFIG_MMCSD
+ /* First, get an instance of the SDIO interface */
+
+ sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
+ if (!sdio) {
+ message("nsh_archinitialize: Failed to initialize SDIO slot %d\n",
+ CONFIG_NSH_MMCSDSLOTNO);
+ return -ENODEV;
+ }
+
+ /* Now bind the SDIO interface to the MMC/SD driver */
+ int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
+ if (ret != OK) {
+ message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+ return ret;
+ }
+
+ /* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */
+ sdio_mediachange(sdio, true);
+
+ message("[boot] Initialized SDIO\n");
+ #endif
+
+ return OK;
+}
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_led.c b/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
new file mode 100644
index 0000000000..a856ccb027
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
@@ -0,0 +1,97 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4fmu2_led.c
+ *
+ * PX4FMU LED backend.
+ */
+
+#include
+
+#include
+
+#include "stm32.h"
+#include "board_config.h"
+
+#include
+
+/*
+ * Ideally we'd be able to get these from up_internal.h,
+ * but since we want to be able to disable the NuttX use
+ * of leds for system indication at will and there is no
+ * separate switch, we need to build independent of the
+ * CONFIG_ARCH_LEDS configuration switch.
+ */
+__BEGIN_DECLS
+extern void led_init();
+extern void led_on(int led);
+extern void led_off(int led);
+extern void led_toggle(int led);
+__END_DECLS
+
+__EXPORT void led_init()
+{
+ /* Configure LED1 GPIO for output */
+
+ stm32_configgpio(GPIO_LED1);
+}
+
+__EXPORT void led_on(int led)
+{
+ if (led == 1)
+ {
+ /* Pull down to switch on */
+ stm32_gpiowrite(GPIO_LED1, false);
+ }
+}
+
+__EXPORT void led_off(int led)
+{
+ if (led == 1)
+ {
+ /* Pull up to switch off */
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+}
+
+__EXPORT void led_toggle(int led)
+{
+ if (led == 1)
+ {
+ if (stm32_gpioread(GPIO_LED1))
+ stm32_gpiowrite(GPIO_LED1, false);
+ else
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+}
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_can.c b/src/drivers/boards/px4fmu-v2/px4fmu_can.c
new file mode 100644
index 0000000000..f66c7cd79f
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_can.c
@@ -0,0 +1,144 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4fmu_can.c
+ *
+ * Board-specific CAN functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include
+
+#include
+#include
+
+#include
+#include
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "stm32.h"
+#include "stm32_can.h"
+#include "board_config.h"
+
+#ifdef CONFIG_CAN
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
+# undef CONFIG_STM32_CAN2
+#endif
+
+#ifdef CONFIG_STM32_CAN1
+# define CAN_PORT 1
+#else
+# define CAN_PORT 2
+#endif
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing CAN */
+
+#ifdef CONFIG_DEBUG_CAN
+# define candbg dbg
+# define canvdbg vdbg
+# define canlldbg lldbg
+# define canllvdbg llvdbg
+#else
+# define candbg(x...)
+# define canvdbg(x...)
+# define canlldbg(x...)
+# define canllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized) {
+ /* Call stm32_caninitialize() to get an instance of the CAN interface */
+
+ can = stm32_caninitialize(CAN_PORT);
+
+ if (can == NULL) {
+ candbg("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+
+ if (ret < 0) {
+ candbg("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif
\ No newline at end of file
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c
new file mode 100644
index 0000000000..600dfef412
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c
@@ -0,0 +1,105 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * @file px4fmu_pwm_servo.c
+ *
+ * Configuration data for the stm32 pwm_servo driver.
+ *
+ * Note that these arrays must always be fully-sized.
+ */
+
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+
+#include "board_config.h"
+
+__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
+ {
+ .base = STM32_TIM1_BASE,
+ .clock_register = STM32_RCC_APB2ENR,
+ .clock_bit = RCC_APB2ENR_TIM1EN,
+ .clock_freq = STM32_APB2_TIM1_CLKIN
+ },
+ {
+ .base = STM32_TIM4_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM4EN,
+ .clock_freq = STM32_APB1_TIM4_CLKIN
+ }
+};
+
+__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
+ {
+ .gpio = GPIO_TIM1_CH4OUT,
+ .timer_index = 0,
+ .timer_channel = 4,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM1_CH3OUT,
+ .timer_index = 0,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM1_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM1_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH2OUT,
+ .timer_index = 1,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH3OUT,
+ .timer_index = 1,
+ .timer_channel = 3,
+ .default_value = 1000,
+ }
+};
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
new file mode 100644
index 0000000000..09838d02fe
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
@@ -0,0 +1,141 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4fmu_spi.c
+ *
+ * Board-specific SPI functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+#include "board_config.h"
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+__EXPORT void weak_function stm32_spiinitialize(void)
+{
+#ifdef CONFIG_STM32_SPI1
+ stm32_configgpio(GPIO_SPI_CS_GYRO);
+ stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
+ stm32_configgpio(GPIO_SPI_CS_BARO);
+
+ /* De-activate all peripherals,
+ * required for some peripheral
+ * state machines
+ */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+ stm32_configgpio(GPIO_SPI_CS_FRAM);
+ stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
+#endif
+}
+
+__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* SPI select is active low, so write !selected to select the device */
+
+ switch (devid) {
+ case PX4_SPIDEV_GYRO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ break;
+
+ case PX4_SPIDEV_ACCEL_MAG:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ break;
+
+ case PX4_SPIDEV_BARO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
+ break;
+
+ default:
+ break;
+ }
+}
+
+__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+
+
+#ifdef CONFIG_STM32_SPI2
+__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there can only be one device on this bus, so always select it */
+ stm32_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
+}
+
+__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ /* FRAM is always present */
+ return SPI_STATUS_PRESENT;
+}
+#endif
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_usb.c b/src/drivers/boards/px4fmu-v2/px4fmu_usb.c
new file mode 100644
index 0000000000..f329e06ff9
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_usb.c
@@ -0,0 +1,108 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4fmu_usb.c
+ *
+ * Board-specific USB functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include
+
+#include
+#include
+#include
+#include
+
+#include
+#include
+
+#include
+#include
+#include "board_config.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_usbinitialize(void)
+{
+ /* The OTG FS has an internal soft pull-up */
+
+ /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
+
+#ifdef CONFIG_STM32_OTGFS
+ stm32_configgpio(GPIO_OTGFS_VBUS);
+ /* XXX We only support device mode
+ stm32_configgpio(GPIO_OTGFS_PWRON);
+ stm32_configgpio(GPIO_OTGFS_OVER);
+ */
+#endif
+}
+
+/************************************************************************************
+ * Name: stm32_usbsuspend
+ *
+ * Description:
+ * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
+ * used. This function is called whenever the USB enters or leaves suspend mode.
+ * This is an opportunity for the board logic to shutdown clocks, power, etc.
+ * while the USB is suspended.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+{
+ ulldbg("resume: %d\n", resume);
+}
+
diff --git a/src/drivers/boards/px4io/px4io_internal.h b/src/drivers/boards/px4io-v1/board_config.h
similarity index 92%
rename from src/drivers/boards/px4io/px4io_internal.h
rename to src/drivers/boards/px4io-v1/board_config.h
index 6638e715ef..48aadbd768 100644
--- a/src/drivers/boards/px4io/px4io_internal.h
+++ b/src/drivers/boards/px4io-v1/board_config.h
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file px4io_internal.h
+ * @file board_config.h
*
* PX4IO hardware definitions.
*/
@@ -47,7 +47,9 @@
#include
#include
+/* these headers are not C++ safe */
#include
+#include
/************************************************************************************
* Definitions
@@ -83,3 +85,11 @@
#define GPIO_ADC_VBATT (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
#define GPIO_ADC_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
+
+/*
+ * High-resolution timer
+ */
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
+#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
+#define GPIO_PPM_IN GPIO_TIM1_CH1IN
diff --git a/src/drivers/boards/px4io/module.mk b/src/drivers/boards/px4io-v1/module.mk
similarity index 100%
rename from src/drivers/boards/px4io/module.mk
rename to src/drivers/boards/px4io-v1/module.mk
diff --git a/src/drivers/boards/px4io/px4io_init.c b/src/drivers/boards/px4io-v1/px4io_init.c
similarity index 99%
rename from src/drivers/boards/px4io/px4io_init.c
rename to src/drivers/boards/px4io-v1/px4io_init.c
index 15c59e4236..8292da9e1c 100644
--- a/src/drivers/boards/px4io/px4io_init.c
+++ b/src/drivers/boards/px4io-v1/px4io_init.c
@@ -55,7 +55,7 @@
#include
#include "stm32.h"
-#include "px4io_internal.h"
+#include "board_config.h"
#include "stm32_uart.h"
#include
diff --git a/src/drivers/boards/px4io/px4io_pwm_servo.c b/src/drivers/boards/px4io-v1/px4io_pwm_servo.c
similarity index 100%
rename from src/drivers/boards/px4io/px4io_pwm_servo.c
rename to src/drivers/boards/px4io-v1/px4io_pwm_servo.c
diff --git a/src/drivers/boards/px4io-v2/board_config.h b/src/drivers/boards/px4io-v2/board_config.h
new file mode 100644
index 0000000000..4d41d0d07e
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/board_config.h
@@ -0,0 +1,138 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4iov2_internal.h
+ *
+ * PX4IOV2 internal definitions
+ */
+
+#pragma once
+
+/******************************************************************************
+ * Included Files
+ ******************************************************************************/
+
+#include
+#include
+#include
+
+/* these headers are not C++ safe */
+#include
+#include
+
+/******************************************************************************
+ * Definitions
+ ******************************************************************************/
+/* Configuration **************************************************************/
+
+/******************************************************************************
+ * Serial
+ ******************************************************************************/
+#define PX4FMU_SERIAL_BASE STM32_USART2_BASE
+#define PX4FMU_SERIAL_VECTOR STM32_IRQ_USART2
+#define PX4FMU_SERIAL_TX_GPIO GPIO_USART2_TX
+#define PX4FMU_SERIAL_RX_GPIO GPIO_USART2_RX
+#define PX4FMU_SERIAL_TX_DMA DMACHAN_USART2_TX
+#define PX4FMU_SERIAL_RX_DMA DMACHAN_USART2_RX
+#define PX4FMU_SERIAL_CLOCK STM32_PCLK1_FREQUENCY
+#define PX4FMU_SERIAL_BITRATE 1500000
+
+/******************************************************************************
+ * GPIOS
+ ******************************************************************************/
+
+/* LEDS **********************************************************************/
+
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14)
+#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
+#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN13)
+
+/* Safety switch button *******************************************************/
+
+#define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5)
+
+/* Power switch controls ******************************************************/
+
+#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
+
+#define GPIO_SERVO_FAULT_DETECT (GPIO_INPUT|GPIO_CNF_INPULLUP|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
+
+/* Analog inputs **************************************************************/
+
+#define GPIO_ADC_VSERVO (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
+
+/* the same rssi signal goes to both an adc and a timer input */
+#define GPIO_ADC_RSSI (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
+#define GPIO_TIM_RSSI (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
+
+/* PWM pins **************************************************************/
+
+#define GPIO_PPM (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8)
+
+#define GPIO_PWM1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_PWM2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_PWM3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
+#define GPIO_PWM4 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
+#define GPIO_PWM5 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN6)
+#define GPIO_PWM6 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7)
+#define GPIO_PWM7 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_PWM8 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
+
+/* SBUS pins *************************************************************/
+
+/* XXX these should be UART pins */
+#define GPIO_SBUS_INPUT (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_SBUS_OUTPUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_SBUS_OENABLE (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN4)
+
+/*
+ * High-resolution timer
+ */
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
+#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
+#define GPIO_PPM_IN GPIO_TIM1_CH1IN
+
+/* LED definitions ******************************************************************/
+/* PX4 has two LEDs that we will encode as: */
+
+#define LED_STARTED 0 /* LED? */
+#define LED_HEAPALLOCATE 1 /* LED? */
+#define LED_IRQSENABLED 2 /* LED? + LED? */
+#define LED_STACKCREATED 3 /* LED? */
+#define LED_INIRQ 4 /* LED? + LED? */
+#define LED_SIGNAL 5 /* LED? + LED? */
+#define LED_ASSERTION 6 /* LED? + LED? + LED? */
+#define LED_PANIC 7 /* N/C + N/C + N/C + LED? */
+
diff --git a/src/drivers/boards/px4io-v2/module.mk b/src/drivers/boards/px4io-v2/module.mk
new file mode 100644
index 0000000000..85f94e8be1
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/module.mk
@@ -0,0 +1,6 @@
+#
+# Board-specific startup code for the PX4IOv2
+#
+
+SRCS = px4iov2_init.c \
+ px4iov2_pwm_servo.c
diff --git a/src/drivers/boards/px4io-v2/px4iov2_init.c b/src/drivers/boards/px4io-v2/px4iov2_init.c
new file mode 100644
index 0000000000..ccd01edf56
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/px4iov2_init.c
@@ -0,0 +1,160 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4iov2_init.c
+ *
+ * PX4FMU-specific early startup code. This file implements the
+ * nsh_archinitialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialisation.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include
+
+#include
+#include
+#include
+#include
+
+#include
+
+#include
+#include "board_config.h"
+
+#include
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+
+ /* configure GPIOs */
+
+ /* LEDS - default to off */
+ stm32_configgpio(GPIO_LED1);
+ stm32_configgpio(GPIO_LED2);
+ stm32_configgpio(GPIO_LED3);
+
+ stm32_configgpio(GPIO_BTN_SAFETY);
+
+ /* spektrum power enable is active high - enable it by default */
+ stm32_configgpio(GPIO_SPEKTRUM_PWR_EN);
+
+ stm32_configgpio(GPIO_SERVO_FAULT_DETECT);
+
+ /* RSSI inputs */
+ stm32_configgpio(GPIO_TIM_RSSI); /* xxx alternate function */
+ stm32_configgpio(GPIO_ADC_RSSI);
+
+ /* servo rail voltage */
+ stm32_configgpio(GPIO_ADC_VSERVO);
+
+ stm32_configgpio(GPIO_SBUS_INPUT); /* xxx alternate function */
+
+ stm32_gpiowrite(GPIO_SBUS_OUTPUT, false);
+ stm32_configgpio(GPIO_SBUS_OUTPUT);
+
+ /* sbus output enable is active low - disable it by default */
+ stm32_gpiowrite(GPIO_SBUS_OENABLE, true);
+ stm32_configgpio(GPIO_SBUS_OENABLE);
+
+ stm32_configgpio(GPIO_PPM); /* xxx alternate function */
+
+ stm32_gpiowrite(GPIO_PWM1, false);
+ stm32_configgpio(GPIO_PWM1);
+
+ stm32_gpiowrite(GPIO_PWM2, false);
+ stm32_configgpio(GPIO_PWM2);
+
+ stm32_gpiowrite(GPIO_PWM3, false);
+ stm32_configgpio(GPIO_PWM3);
+
+ stm32_gpiowrite(GPIO_PWM4, false);
+ stm32_configgpio(GPIO_PWM4);
+
+ stm32_gpiowrite(GPIO_PWM5, false);
+ stm32_configgpio(GPIO_PWM5);
+
+ stm32_gpiowrite(GPIO_PWM6, false);
+ stm32_configgpio(GPIO_PWM6);
+
+ stm32_gpiowrite(GPIO_PWM7, false);
+ stm32_configgpio(GPIO_PWM7);
+
+ stm32_gpiowrite(GPIO_PWM8, false);
+ stm32_configgpio(GPIO_PWM8);
+}
diff --git a/src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c b/src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c
new file mode 100644
index 0000000000..4f1b9487cf
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c
@@ -0,0 +1,123 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * @file px4iov2_pwm_servo.c
+ *
+ * Configuration data for the stm32 pwm_servo driver.
+ *
+ * Note that these arrays must always be fully-sized.
+ */
+
+#include
+
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+
+__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
+ {
+ .base = STM32_TIM2_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM2EN,
+ .clock_freq = STM32_APB1_TIM2_CLKIN
+ },
+ {
+ .base = STM32_TIM3_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM3EN,
+ .clock_freq = STM32_APB1_TIM3_CLKIN
+ },
+ {
+ .base = STM32_TIM4_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM4EN,
+ .clock_freq = STM32_APB1_TIM4_CLKIN
+ }
+};
+
+__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
+ {
+ .gpio = GPIO_TIM2_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM2_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH3OUT,
+ .timer_index = 2,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH4OUT,
+ .timer_index = 2,
+ .timer_channel = 4,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH1OUT,
+ .timer_index = 1,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH2OUT,
+ .timer_index = 1,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH3OUT,
+ .timer_index = 1,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH4OUT,
+ .timer_index = 1,
+ .timer_channel = 4,
+ .default_value = 1000,
+ }
+};
diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h
index dc0c84052b..a9e22eaa6b 100644
--- a/src/drivers/device/ringbuffer.h
+++ b/src/drivers/device/ringbuffer.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,15 +34,14 @@
/**
* @file ringbuffer.h
*
- * A simple ringbuffer template.
+ * A flexible ringbuffer class.
*/
#pragma once
-template
class RingBuffer {
public:
- RingBuffer(unsigned size);
+ RingBuffer(unsigned ring_size, size_t entry_size);
virtual ~RingBuffer();
/**
@@ -52,15 +50,37 @@ public:
* @param val Item to put
* @return true if the item was put, false if the buffer is full
*/
- bool put(T &val);
+ bool put(const void *val, size_t val_size = 0);
+
+ bool put(int8_t val);
+ bool put(uint8_t val);
+ bool put(int16_t val);
+ bool put(uint16_t val);
+ bool put(int32_t val);
+ bool put(uint32_t val);
+ bool put(int64_t val);
+ bool put(uint64_t val);
+ bool put(float val);
+ bool put(double val);
/**
- * Put an item into the buffer.
+ * Force an item into the buffer, discarding an older item if there is not space.
*
* @param val Item to put
- * @return true if the item was put, false if the buffer is full
+ * @return true if an item was discarded to make space
*/
- bool put(const T &val);
+ bool force(const void *val, size_t val_size = 0);
+
+ bool force(int8_t val);
+ bool force(uint8_t val);
+ bool force(int16_t val);
+ bool force(uint16_t val);
+ bool force(int32_t val);
+ bool force(uint32_t val);
+ bool force(int64_t val);
+ bool force(uint64_t val);
+ bool force(float val);
+ bool force(double val);
/**
* Get an item from the buffer.
@@ -68,15 +88,18 @@ public:
* @param val Item that was gotten
* @return true if an item was got, false if the buffer was empty.
*/
- bool get(T &val);
+ bool get(void *val, size_t val_size = 0);
- /**
- * Get an item from the buffer (scalars only).
- *
- * @return The value that was fetched, or zero if the buffer was
- * empty.
- */
- T get(void);
+ bool get(int8_t &val);
+ bool get(uint8_t &val);
+ bool get(int16_t &val);
+ bool get(uint16_t &val);
+ bool get(int32_t &val);
+ bool get(uint32_t &val);
+ bool get(int64_t &val);
+ bool get(uint64_t &val);
+ bool get(float &val);
+ bool get(double &val);
/*
* Get the number of slots free in the buffer.
@@ -97,54 +120,103 @@ public:
/*
* Returns true if the buffer is empty.
*/
- bool empty() { return _tail == _head; }
+ bool empty();
/*
* Returns true if the buffer is full.
*/
- bool full() { return _next(_head) == _tail; }
+ bool full();
/*
* Returns the capacity of the buffer, or zero if the buffer could
* not be allocated.
*/
- unsigned size() { return (_buf != nullptr) ? _size : 0; }
+ unsigned size();
/*
* Empties the buffer.
*/
- void flush() { _head = _tail = _size; }
+ void flush();
+
+ /*
+ * resize the buffer. This is unsafe to be called while
+ * a producer or consuming is running. Caller is responsible
+ * for any locking needed
+ *
+ * @param new_size new size for buffer
+ * @return true if the resize succeeds, false if
+ * not (allocation error)
+ */
+ bool resize(unsigned new_size);
+
+ /*
+ * printf() some info on the buffer
+ */
+ void print_info(const char *name);
private:
- T *const _buf;
- const unsigned _size;
- volatile unsigned _head; /**< insertion point */
- volatile unsigned _tail; /**< removal point */
+ unsigned _num_items;
+ const size_t _item_size;
+ char *_buf;
+ volatile unsigned _head; /**< insertion point in _item_size units */
+ volatile unsigned _tail; /**< removal point in _item_size units */
unsigned _next(unsigned index);
};
-template
-RingBuffer::RingBuffer(unsigned with_size) :
- _buf(new T[with_size + 1]),
- _size(with_size),
- _head(with_size),
- _tail(with_size)
+RingBuffer::RingBuffer(unsigned num_items, size_t item_size) :
+ _num_items(num_items),
+ _item_size(item_size),
+ _buf(new char[(_num_items+1) * item_size]),
+ _head(_num_items),
+ _tail(_num_items)
{}
-template
-RingBuffer::~RingBuffer()
+RingBuffer::~RingBuffer()
{
if (_buf != nullptr)
delete[] _buf;
}
-template
-bool RingBuffer::put(T &val)
+unsigned
+RingBuffer::_next(unsigned index)
+{
+ return (0 == index) ? _num_items : (index - 1);
+}
+
+bool
+RingBuffer::empty()
+{
+ return _tail == _head;
+}
+
+bool
+RingBuffer::full()
+{
+ return _next(_head) == _tail;
+}
+
+unsigned
+RingBuffer::size()
+{
+ return (_buf != nullptr) ? _num_items : 0;
+}
+
+void
+RingBuffer::flush()
+{
+ while (!empty())
+ get(NULL);
+}
+
+bool
+RingBuffer::put(const void *val, size_t val_size)
{
unsigned next = _next(_head);
if (next != _tail) {
- _buf[_head] = val;
+ if ((val_size == 0) || (val_size > _item_size))
+ val_size = _item_size;
+ memcpy(&_buf[_head * _item_size], val, val_size);
_head = next;
return true;
} else {
@@ -152,52 +224,286 @@ bool RingBuffer::put(T &val)
}
}
-template
-bool RingBuffer::put(const T &val)
+bool
+RingBuffer::put(int8_t val)
{
- unsigned next = _next(_head);
- if (next != _tail) {
- _buf[_head] = val;
- _head = next;
- return true;
- } else {
- return false;
- }
+ return put(&val, sizeof(val));
}
-template
-bool RingBuffer::get(T &val)
+bool
+RingBuffer::put(uint8_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(int16_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(uint16_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(int32_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(uint32_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(int64_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(uint64_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(float val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(double val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(const void *val, size_t val_size)
+{
+ bool overwrote = false;
+
+ for (;;) {
+ if (put(val, val_size))
+ break;
+ get(NULL);
+ overwrote = true;
+ }
+ return overwrote;
+}
+
+bool
+RingBuffer::force(int8_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(uint8_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(int16_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(uint16_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(int32_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(uint32_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(int64_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(uint64_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(float val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(double val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(void *val, size_t val_size)
{
if (_tail != _head) {
- val = _buf[_tail];
- _tail = _next(_tail);
+ unsigned candidate;
+ unsigned next;
+
+ if ((val_size == 0) || (val_size > _item_size))
+ val_size = _item_size;
+
+ do {
+ /* decide which element we think we're going to read */
+ candidate = _tail;
+
+ /* and what the corresponding next index will be */
+ next = _next(candidate);
+
+ /* go ahead and read from this index */
+ if (val != NULL)
+ memcpy(val, &_buf[candidate * _item_size], val_size);
+
+ /* if the tail pointer didn't change, we got our item */
+ } while (!__sync_bool_compare_and_swap(&_tail, candidate, next));
+
return true;
} else {
return false;
}
}
-template
-T RingBuffer::get(void)
+bool
+RingBuffer::get(int8_t &val)
{
- T val;
- return get(val) ? val : 0;
+ return get(&val, sizeof(val));
}
-template
-unsigned RingBuffer::space(void)
+bool
+RingBuffer::get(uint8_t &val)
{
- return (_tail >= _head) ? (_size - (_tail - _head)) : (_head - _tail - 1);
+ return get(&val, sizeof(val));
}
-template
-unsigned RingBuffer::count(void)
+bool
+RingBuffer::get(int16_t &val)
{
- return _size - space();
+ return get(&val, sizeof(val));
}
-template
-unsigned RingBuffer::_next(unsigned index)
+bool
+RingBuffer::get(uint16_t &val)
{
- return (0 == index) ? _size : (index - 1);
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(int32_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(uint32_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(int64_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(uint64_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(float &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(double &val)
+{
+ return get(&val, sizeof(val));
+}
+
+unsigned
+RingBuffer::space(void)
+{
+ unsigned tail, head;
+
+ /*
+ * Make a copy of the head/tail pointers in a fashion that
+ * may err on the side of under-estimating the free space
+ * in the buffer in the case that the buffer is being updated
+ * asynchronously with our check.
+ * If the head pointer changes (reducing space) while copying,
+ * re-try the copy.
+ */
+ do {
+ head = _head;
+ tail = _tail;
+ } while (head != _head);
+
+ return (tail >= head) ? (_num_items - (tail - head)) : (head - tail - 1);
+}
+
+unsigned
+RingBuffer::count(void)
+{
+ /*
+ * Note that due to the conservative nature of space(), this may
+ * over-estimate the number of items in the buffer.
+ */
+ return _num_items - space();
+}
+
+bool
+RingBuffer::resize(unsigned new_size)
+{
+ char *old_buffer;
+ char *new_buffer = new char [(new_size+1) * _item_size];
+ if (new_buffer == nullptr) {
+ return false;
+ }
+ old_buffer = _buf;
+ _buf = new_buffer;
+ _num_items = new_size;
+ _head = new_size;
+ _tail = new_size;
+ delete[] old_buffer;
+ return true;
+}
+
+void
+RingBuffer::print_info(const char *name)
+{
+ printf("%s %u/%u (%u/%u @ %p)\n",
+ name,
+ _num_items,
+ _num_items * _item_size,
+ _head,
+ _tail,
+ _buf);
}
diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp
index 8fffd60cb4..fa6b78d640 100644
--- a/src/drivers/device/spi.cpp
+++ b/src/drivers/device/spi.cpp
@@ -67,6 +67,7 @@ SPI::SPI(const char *name,
CDev(name, devname, irq),
// public
// protected
+ locking_mode(LOCK_PREEMPTION),
// private
_bus(bus),
_device(device),
@@ -132,13 +133,25 @@ SPI::probe()
int
SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
{
+ irqstate_t state;
if ((send == nullptr) && (recv == nullptr))
return -EINVAL;
- /* do common setup */
- if (!up_interrupt_context())
- SPI_LOCK(_dev, true);
+ /* lock the bus as required */
+ if (!up_interrupt_context()) {
+ switch (locking_mode) {
+ default:
+ case LOCK_PREEMPTION:
+ state = irqsave();
+ break;
+ case LOCK_THREADS:
+ SPI_LOCK(_dev, true);
+ break;
+ case LOCK_NONE:
+ break;
+ }
+ }
SPI_SETFREQUENCY(_dev, _frequency);
SPI_SETMODE(_dev, _mode);
@@ -151,8 +164,19 @@ SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
/* and clean up */
SPI_SELECT(_dev, _device, false);
- if (!up_interrupt_context())
- SPI_LOCK(_dev, false);
+ if (!up_interrupt_context()) {
+ switch (locking_mode) {
+ default:
+ case LOCK_PREEMPTION:
+ irqrestore(state);
+ break;
+ case LOCK_THREADS:
+ SPI_LOCK(_dev, false);
+ break;
+ case LOCK_NONE:
+ break;
+ }
+ }
return OK;
}
diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h
index e0122372a0..9103dca2ea 100644
--- a/src/drivers/device/spi.h
+++ b/src/drivers/device/spi.h
@@ -101,6 +101,17 @@ protected:
*/
int transfer(uint8_t *send, uint8_t *recv, unsigned len);
+ /**
+ * Locking modes supported by the driver.
+ */
+ enum LockMode {
+ LOCK_PREEMPTION, /**< the default; lock against all forms of preemption. */
+ LOCK_THREADS, /**< lock only against other threads, using SPI_LOCK */
+ LOCK_NONE /**< perform no locking, only safe if the bus is entirely private */
+ };
+
+ LockMode locking_mode; /**< selected locking mode */
+
private:
int _bus;
enum spi_dev_e _device;
diff --git a/src/drivers/drv_accel.h b/src/drivers/drv_accel.h
index 794de584b6..7d93ed9383 100644
--- a/src/drivers/drv_accel.h
+++ b/src/drivers/drv_accel.h
@@ -32,7 +32,9 @@
****************************************************************************/
/**
- * @file Accelerometer driver interface.
+ * @file drv_accel.h
+ *
+ * Accelerometer driver interface.
*/
#ifndef _DRV_ACCEL_H
@@ -52,6 +54,7 @@
*/
struct accel_report {
uint64_t timestamp;
+ uint64_t error_count;
float x; /**< acceleration in the NED X board axis in m/s^2 */
float y; /**< acceleration in the NED Y board axis in m/s^2 */
float z; /**< acceleration in the NED Z board axis in m/s^2 */
@@ -65,7 +68,7 @@ struct accel_report {
int16_t temperature_raw;
};
-/** accel scaling factors; Vout = (Vin * Vscale) + Voffset */
+/** accel scaling factors; Vout = Vscale * (Vin + Voffset) */
struct accel_scale {
float x_offset;
float x_scale;
diff --git a/src/drivers/drv_airspeed.h b/src/drivers/drv_airspeed.h
index 7bb9ee2af1..78f31495d9 100644
--- a/src/drivers/drv_airspeed.h
+++ b/src/drivers/drv_airspeed.h
@@ -32,7 +32,10 @@
****************************************************************************/
/**
- * @file Airspeed driver interface.
+ * @file drv_airspeed.h
+ *
+ * Airspeed driver interface.
+ *
* @author Simon Wilks
*/
diff --git a/src/drivers/drv_baro.h b/src/drivers/drv_baro.h
index 176f798c06..e2f0137ae2 100644
--- a/src/drivers/drv_baro.h
+++ b/src/drivers/drv_baro.h
@@ -32,7 +32,9 @@
****************************************************************************/
/**
- * @file Barometric pressure sensor driver interface.
+ * @file drv_baro.h
+ *
+ * Barometric pressure sensor driver interface.
*/
#ifndef _DRV_BARO_H
@@ -55,6 +57,7 @@ struct baro_report {
float altitude;
float temperature;
uint64_t timestamp;
+ uint64_t error_count;
};
/*
diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h
index 510983d4bd..37af26d522 100644
--- a/src/drivers/drv_gpio.h
+++ b/src/drivers/drv_gpio.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -59,17 +59,47 @@
# define GPIO_CAN_RX (1<<7) /**< CAN2 RX */
/**
- * Default GPIO device - other devices may also support this protocol if
- * they also export GPIO-like things. This is always the GPIOs on the
- * main board.
+ * Device paths for things that support the GPIO ioctl protocol.
*/
# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
# define PX4IO_DEVICE_PATH "/dev/px4io"
#endif
-#ifndef PX4IO_DEVICE_PATH
-# error No GPIO support for this board.
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+/*
+ * PX4FMUv2 GPIO numbers.
+ *
+ * There are no alternate functions on this board.
+ */
+# define GPIO_SERVO_1 (1<<0) /**< servo 1 output */
+# define GPIO_SERVO_2 (1<<1) /**< servo 2 output */
+# define GPIO_SERVO_3 (1<<2) /**< servo 3 output */
+# define GPIO_SERVO_4 (1<<3) /**< servo 4 output */
+# define GPIO_SERVO_5 (1<<4) /**< servo 5 output */
+# define GPIO_SERVO_6 (1<<5) /**< servo 6 output */
+
+# define GPIO_5V_PERIPH_EN (1<<6) /**< PA8 - !VDD_5V_PERIPH_EN */
+# define GPIO_3V3_SENSORS_EN (1<<7) /**< PE3 - VDD_3V3_SENSORS_EN */
+# define GPIO_BRICK_VALID (1<<8) /**< PB5 - !VDD_BRICK_VALID */
+# define GPIO_SERVO_VALID (1<<9) /**< PB7 - !VDD_SERVO_VALID */
+# define GPIO_5V_HIPOWER_OC (1<<10) /**< PE10 - !VDD_5V_HIPOWER_OC */
+# define GPIO_5V_PERIPH_OC (1<<11) /**< PE10 - !VDD_5V_PERIPH_OC */
+
+/**
+ * Device paths for things that support the GPIO ioctl protocol.
+ */
+# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
+# define PX4IO_DEVICE_PATH "/dev/px4io"
+
+#endif
+
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
+/* no GPIO driver on the PX4IOv1 board */
+#endif
+
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+/* no GPIO driver on the PX4IOv2 board */
#endif
/*
diff --git a/src/drivers/drv_gps.h b/src/drivers/drv_gps.h
index 1dda8ef0b8..06e3535b30 100644
--- a/src/drivers/drv_gps.h
+++ b/src/drivers/drv_gps.h
@@ -32,7 +32,9 @@
****************************************************************************/
/**
- * @file GPS driver interface.
+ * @file drv_gps.h
+ *
+ * GPS driver interface.
*/
#ifndef _DRV_GPS_H
@@ -51,8 +53,7 @@
typedef enum {
GPS_DRIVER_MODE_NONE = 0,
GPS_DRIVER_MODE_UBX,
- GPS_DRIVER_MODE_MTK,
- GPS_DRIVER_MODE_NMEA,
+ GPS_DRIVER_MODE_MTK
} gps_driver_mode_t;
diff --git a/src/drivers/drv_gyro.h b/src/drivers/drv_gyro.h
index 1d0fef6fcc..2ae8c70582 100644
--- a/src/drivers/drv_gyro.h
+++ b/src/drivers/drv_gyro.h
@@ -32,7 +32,9 @@
****************************************************************************/
/**
- * @file Gyroscope driver interface.
+ * @file drv_gyro.h
+ *
+ * Gyroscope driver interface.
*/
#ifndef _DRV_GYRO_H
@@ -52,6 +54,7 @@
*/
struct gyro_report {
uint64_t timestamp;
+ uint64_t error_count;
float x; /**< angular velocity in the NED X board axis in rad/s */
float y; /**< angular velocity in the NED Y board axis in rad/s */
float z; /**< angular velocity in the NED Z board axis in rad/s */
diff --git a/src/drivers/drv_led.h b/src/drivers/drv_led.h
index 21044f6200..4ce04696e0 100644
--- a/src/drivers/drv_led.h
+++ b/src/drivers/drv_led.h
@@ -54,12 +54,13 @@
#define LED_ON _IOC(_LED_BASE, 0)
#define LED_OFF _IOC(_LED_BASE, 1)
+#define LED_TOGGLE _IOC(_LED_BASE, 2)
__BEGIN_DECLS
/*
* Initialise the LED driver.
*/
-__EXPORT extern void drv_led_start(void);
+__EXPORT void drv_led_start(void);
__END_DECLS
diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h
index 9aab995a17..06107bd3d1 100644
--- a/src/drivers/drv_mag.h
+++ b/src/drivers/drv_mag.h
@@ -54,6 +54,7 @@
*/
struct mag_report {
uint64_t timestamp;
+ uint64_t error_count;
float x;
float y;
float z;
@@ -90,25 +91,37 @@ ORB_DECLARE(sensor_mag);
/** set the mag internal sample rate to at least (arg) Hz */
#define MAGIOCSSAMPLERATE _MAGIOC(0)
+/** return the mag internal sample rate in Hz */
+#define MAGIOCGSAMPLERATE _MAGIOC(1)
+
/** set the mag internal lowpass filter to no lower than (arg) Hz */
-#define MAGIOCSLOWPASS _MAGIOC(1)
+#define MAGIOCSLOWPASS _MAGIOC(2)
+
+/** return the mag internal lowpass filter in Hz */
+#define MAGIOCGLOWPASS _MAGIOC(3)
/** set the mag scaling constants to the structure pointed to by (arg) */
-#define MAGIOCSSCALE _MAGIOC(2)
+#define MAGIOCSSCALE _MAGIOC(4)
/** copy the mag scaling constants to the structure pointed to by (arg) */
-#define MAGIOCGSCALE _MAGIOC(3)
+#define MAGIOCGSCALE _MAGIOC(5)
/** set the measurement range to handle (at least) arg Gauss */
-#define MAGIOCSRANGE _MAGIOC(4)
+#define MAGIOCSRANGE _MAGIOC(6)
+
+/** return the current mag measurement range in Gauss */
+#define MAGIOCGRANGE _MAGIOC(7)
/** perform self-calibration, update scale factors to canonical units */
-#define MAGIOCCALIBRATE _MAGIOC(5)
+#define MAGIOCCALIBRATE _MAGIOC(8)
/** excite strap */
-#define MAGIOCEXSTRAP _MAGIOC(6)
+#define MAGIOCEXSTRAP _MAGIOC(9)
/** perform self test and report status */
-#define MAGIOCSELFTEST _MAGIOC(7)
+#define MAGIOCSELFTEST _MAGIOC(10)
+
+/** determine if mag is external or onboard */
+#define MAGIOCGEXTERNAL _MAGIOC(11)
#endif /* _DRV_MAG_H */
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index ec9d4ca098..51f916f37b 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -64,6 +64,36 @@ __BEGIN_DECLS
*/
#define PWM_OUTPUT_MAX_CHANNELS 16
+/**
+ * Lowest minimum PWM in us
+ */
+#define PWM_LOWEST_MIN 900
+
+/**
+ * Default minimum PWM in us
+ */
+#define PWM_DEFAULT_MIN 1000
+
+/**
+ * Highest PWM allowed as the minimum PWM
+ */
+#define PWM_HIGHEST_MIN 1300
+
+/**
+ * Highest maximum PWM in us
+ */
+#define PWM_HIGHEST_MAX 2100
+
+/**
+ * Default maximum PWM in us
+ */
+#define PWM_DEFAULT_MAX 2000
+
+/**
+ * Lowest PWM allowed as the maximum PWM
+ */
+#define PWM_LOWEST_MAX 1700
+
/**
* Servo output signal type, value is actual servo output pulse
* width in microseconds.
@@ -79,6 +109,7 @@ typedef uint16_t servo_position_t;
struct pwm_output_values {
/** desired pulse widths for each of the supported channels */
servo_position_t values[PWM_OUTPUT_MAX_CHANNELS];
+ unsigned channel_count;
};
/*
@@ -100,26 +131,63 @@ ORB_DECLARE(output_pwm);
/** disarm all servo outputs (stop generating pulses) */
#define PWM_SERVO_DISARM _IOC(_PWM_SERVO_BASE, 1)
+/** get default servo update rate */
+#define PWM_SERVO_GET_DEFAULT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 2)
+
/** set alternate servo update rate */
-#define PWM_SERVO_SET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 2)
+#define PWM_SERVO_SET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 3)
+
+/** get alternate servo update rate */
+#define PWM_SERVO_GET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 4)
/** get the number of servos in *(unsigned *)arg */
-#define PWM_SERVO_GET_COUNT _IOC(_PWM_SERVO_BASE, 3)
+#define PWM_SERVO_GET_COUNT _IOC(_PWM_SERVO_BASE, 5)
/** selects servo update rates, one bit per servo. 0 = default (50Hz), 1 = alternate */
-#define PWM_SERVO_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 4)
+#define PWM_SERVO_SET_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 6)
+
+/** check the selected update rates */
+#define PWM_SERVO_GET_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 7)
/** set the 'ARM ok' bit, which activates the safety switch */
-#define PWM_SERVO_SET_ARM_OK _IOC(_PWM_SERVO_BASE, 5)
+#define PWM_SERVO_SET_ARM_OK _IOC(_PWM_SERVO_BASE, 8)
/** clear the 'ARM ok' bit, which deactivates the safety switch */
-#define PWM_SERVO_CLEAR_ARM_OK _IOC(_PWM_SERVO_BASE, 6)
+#define PWM_SERVO_CLEAR_ARM_OK _IOC(_PWM_SERVO_BASE, 9)
/** start DSM bind */
-#define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 7)
+#define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 10)
-/** Power up DSM receiver */
-#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 8)
+#define DSM2_BIND_PULSES 3 /* DSM_BIND_START ioctl parameter, pulses required to start dsm2 pairing */
+#define DSMX_BIND_PULSES 7 /* DSM_BIND_START ioctl parameter, pulses required to start dsmx pairing */
+#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
+
+/** power up DSM receiver */
+#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 11)
+
+/** set the PWM value for failsafe */
+#define PWM_SERVO_SET_FAILSAFE_PWM _IOC(_PWM_SERVO_BASE, 12)
+
+/** get the PWM value for failsafe */
+#define PWM_SERVO_GET_FAILSAFE_PWM _IOC(_PWM_SERVO_BASE, 13)
+
+/** set the PWM value when disarmed - should be no PWM (zero) by default */
+#define PWM_SERVO_SET_DISARMED_PWM _IOC(_PWM_SERVO_BASE, 14)
+
+/** get the PWM value when disarmed */
+#define PWM_SERVO_GET_DISARMED_PWM _IOC(_PWM_SERVO_BASE, 15)
+
+/** set the minimum PWM value the output will send */
+#define PWM_SERVO_SET_MIN_PWM _IOC(_PWM_SERVO_BASE, 16)
+
+/** get the minimum PWM value the output will send */
+#define PWM_SERVO_GET_MIN_PWM _IOC(_PWM_SERVO_BASE, 17)
+
+/** set the maximum PWM value the output will send */
+#define PWM_SERVO_SET_MAX_PWM _IOC(_PWM_SERVO_BASE, 18)
+
+/** get the maximum PWM value the output will send */
+#define PWM_SERVO_GET_MAX_PWM _IOC(_PWM_SERVO_BASE, 19)
/** set a single servo to a specific value */
#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo)
diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h
index 03a82ec5d0..cf91f70304 100644
--- a/src/drivers/drv_range_finder.h
+++ b/src/drivers/drv_range_finder.h
@@ -52,6 +52,7 @@
*/
struct range_finder_report {
uint64_t timestamp;
+ uint64_t error_count;
float distance; /** in meters */
uint8_t valid; /** 1 == within sensor range, 0 = outside sensor range */
};
diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h
index 4decc324ef..78ffad9d7b 100644
--- a/src/drivers/drv_rc_input.h
+++ b/src/drivers/drv_rc_input.h
@@ -32,8 +32,9 @@
****************************************************************************/
/**
- * @file R/C input interface.
+ * @file drv_rc_input.h
*
+ * R/C input interface.
*/
#ifndef _DRV_RC_INPUT_H
diff --git a/src/drivers/drv_rgbled.h b/src/drivers/drv_rgbled.h
new file mode 100644
index 0000000000..07c6186dde
--- /dev/null
+++ b/src/drivers/drv_rgbled.h
@@ -0,0 +1,128 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file drv_rgbled.h
+ *
+ * RGB led device API
+ */
+
+#pragma once
+
+#include
+#include
+
+/* more devices will be 1, 2, etc */
+#define RGBLED_DEVICE_PATH "/dev/rgbled0"
+
+/*
+ * ioctl() definitions
+ */
+
+#define _RGBLEDIOCBASE (0x2900)
+#define _RGBLEDIOC(_n) (_IOC(_RGBLEDIOCBASE, _n))
+
+/** play the named script in *(char *)arg, repeating forever */
+#define RGBLED_PLAY_SCRIPT_NAMED _RGBLEDIOC(1)
+
+/** play the numbered script in (arg), repeating forever */
+#define RGBLED_PLAY_SCRIPT _RGBLEDIOC(2)
+
+/**
+ * Set the user script; (arg) is a pointer to an array of script lines,
+ * where each line is an array of four bytes giving , , arg[0-2]
+ *
+ * The script is terminated by a zero command.
+ */
+#define RGBLED_SET_USER_SCRIPT _RGBLEDIOC(3)
+
+/** set constant RGB values */
+#define RGBLED_SET_RGB _RGBLEDIOC(4)
+
+/** set color */
+#define RGBLED_SET_COLOR _RGBLEDIOC(5)
+
+/** set blink speed */
+#define RGBLED_SET_MODE _RGBLEDIOC(6)
+
+/** set pattern */
+#define RGBLED_SET_PATTERN _RGBLEDIOC(7)
+
+
+/*
+ structure passed to RGBLED_SET_RGB ioctl()
+ Note that the driver scales the brightness to 0 to 255, regardless
+ of the hardware scaling
+ */
+typedef struct {
+ uint8_t red;
+ uint8_t green;
+ uint8_t blue;
+} rgbled_rgbset_t;
+
+/* enum passed to RGBLED_SET_COLOR ioctl()*/
+typedef enum {
+ RGBLED_COLOR_OFF,
+ RGBLED_COLOR_RED,
+ RGBLED_COLOR_YELLOW,
+ RGBLED_COLOR_PURPLE,
+ RGBLED_COLOR_GREEN,
+ RGBLED_COLOR_BLUE,
+ RGBLED_COLOR_WHITE,
+ RGBLED_COLOR_AMBER,
+ RGBLED_COLOR_DIM_RED,
+ RGBLED_COLOR_DIM_YELLOW,
+ RGBLED_COLOR_DIM_PURPLE,
+ RGBLED_COLOR_DIM_GREEN,
+ RGBLED_COLOR_DIM_BLUE,
+ RGBLED_COLOR_DIM_WHITE,
+ RGBLED_COLOR_DIM_AMBER
+} rgbled_color_t;
+
+/* enum passed to RGBLED_SET_MODE ioctl()*/
+typedef enum {
+ RGBLED_MODE_OFF,
+ RGBLED_MODE_ON,
+ RGBLED_MODE_BLINK_SLOW,
+ RGBLED_MODE_BLINK_NORMAL,
+ RGBLED_MODE_BLINK_FAST,
+ RGBLED_MODE_BREATHE,
+ RGBLED_MODE_PATTERN
+} rgbled_mode_t;
+
+#define RGBLED_PATTERN_LENGTH 20
+
+typedef struct {
+ rgbled_color_t color[RGBLED_PATTERN_LENGTH];
+ unsigned duration[RGBLED_PATTERN_LENGTH];
+} rgbled_pattern_t;
diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h
index 3a89cab9dd..8e8b2c1b95 100644
--- a/src/drivers/drv_sensor.h
+++ b/src/drivers/drv_sensor.h
@@ -32,7 +32,9 @@
****************************************************************************/
/**
- * @file Common sensor API and ioctl definitions.
+ * @file drv_sensor.h
+ *
+ * Common sensor API and ioctl definitions.
*/
#ifndef _DRV_SENSOR_H
diff --git a/src/drivers/drv_tone_alarm.h b/src/drivers/drv_tone_alarm.h
index 0c6afc64c4..cb5fd53a5f 100644
--- a/src/drivers/drv_tone_alarm.h
+++ b/src/drivers/drv_tone_alarm.h
@@ -31,7 +31,9 @@
*
****************************************************************************/
-/*
+/**
+ * @file drv_tone_alarm.h
+ *
* Driver for the PX4 audio alarm port, /dev/tone_alarm.
*
* The tone_alarm driver supports a set of predefined "alarm"
@@ -60,6 +62,8 @@
#include
+#define TONEALARM_DEVICE_PATH "/dev/tone_alarm"
+
#define _TONE_ALARM_BASE 0x7400
#define TONE_SET_ALARM _IOC(_TONE_ALARM_BASE, 1)
@@ -125,4 +129,25 @@ enum tone_pitch {
TONE_NOTE_MAX
};
+enum {
+ TONE_STOP_TUNE = 0,
+ TONE_STARTUP_TUNE,
+ TONE_ERROR_TUNE,
+ TONE_NOTIFY_POSITIVE_TUNE,
+ TONE_NOTIFY_NEUTRAL_TUNE,
+ TONE_NOTIFY_NEGATIVE_TUNE,
+ /* Do not include these unused tunes
+ TONE_CHARGE_TUNE,
+ TONE_DIXIE_TUNE,
+ TONE_CUCURACHA_TUNE,
+ TONE_YANKEE_TUNE,
+ TONE_DAISY_TUNE,
+ TONE_WILLIAM_TELL_TUNE, */
+ TONE_ARMING_WARNING_TUNE,
+ TONE_BATTERY_WARNING_SLOW_TUNE,
+ TONE_BATTERY_WARNING_FAST_TUNE,
+ TONE_GPS_WARNING_TUNE,
+ TONE_NUMBER_OF_TUNES
+};
+
#endif /* DRV_TONE_ALARM_H_ */
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index cd72d9d23d..9d8ad084e5 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -59,7 +59,7 @@
#include
#include
-#include
+#include
#include
#include
@@ -68,6 +68,7 @@
#include
#include
+#include
#include
#include
@@ -131,11 +132,8 @@ ETSAirspeed::measure()
if (OK != ret) {
perf_count(_comms_errors);
log("i2c::transfer returned %d", ret);
- return ret;
}
- ret = OK;
-
return ret;
}
@@ -152,48 +150,44 @@ ETSAirspeed::collect()
ret = transfer(nullptr, 0, &val[0], 2);
if (ret < 0) {
- log("error reading from sensor: %d", ret);
+ perf_count(_comms_errors);
return ret;
}
uint16_t diff_pres_pa = val[1] << 8 | val[0];
if (diff_pres_pa == 0) {
- // a zero value means the pressure sensor cannot give us a
- // value. We need to return, and not report a value or the
- // caller could end up using this value as part of an
- // average
- log("zero value from sensor");
- return -1;
+ // a zero value means the pressure sensor cannot give us a
+ // value. We need to return, and not report a value or the
+ // caller could end up using this value as part of an
+ // average
+ perf_count(_comms_errors);
+ log("zero value from sensor");
+ return -1;
}
if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;
-
} else {
diff_pres_pa -= _diff_pres_offset;
}
- // XXX we may want to smooth out the readings to remove noise.
-
- _reports[_next_report].timestamp = hrt_absolute_time();
- _reports[_next_report].differential_pressure_pa = diff_pres_pa;
-
// Track maximum differential pressure measured (so we can work out top speed).
- if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) {
- _reports[_next_report].max_differential_pressure_pa = diff_pres_pa;
+ if (diff_pres_pa > _max_differential_pressure_pa) {
+ _max_differential_pressure_pa = diff_pres_pa;
}
+ // XXX we may want to smooth out the readings to remove noise.
+ differential_pressure_s report;
+ report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
+ report.differential_pressure_pa = diff_pres_pa;
+ report.voltage = 0;
+ report.max_differential_pressure_pa = _max_differential_pressure_pa;
+
/* announce the airspeed if needed, just publish else */
- orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]);
+ orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report);
- /* post a report to the ring - note, not locked */
- INCREMENT(_next_report, _num_reports);
-
- /* if we are running up against the oldest report, toss it */
- if (_next_report == _oldest_report) {
- perf_count(_buffer_overflows);
- INCREMENT(_oldest_report, _num_reports);
- }
+ new_report(report);
/* notify anyone waiting for data */
poll_notify(POLLIN);
@@ -213,7 +207,7 @@ ETSAirspeed::cycle()
/* perform collection */
if (OK != collect()) {
- log("collection error");
+ perf_count(_comms_errors);
/* restart the measurement state machine */
start();
return;
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index 38835418b0..fc500a9ecd 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -85,7 +85,7 @@ static const int ERROR = -1;
class GPS : public device::CDev
{
public:
- GPS(const char* uart_path);
+ GPS(const char *uart_path);
virtual ~GPS();
virtual int init();
@@ -156,7 +156,7 @@ GPS *g_dev;
}
-GPS::GPS(const char* uart_path) :
+GPS::GPS(const char *uart_path) :
CDev("gps", GPS_DEVICE_PATH),
_task_should_exit(false),
_healthy(false),
@@ -192,6 +192,7 @@ GPS::~GPS()
/* well, kill it anyway, though this will probably crash */
if (_task != -1)
task_delete(_task);
+
g_dev = nullptr;
}
@@ -270,19 +271,20 @@ GPS::task_main()
}
switch (_mode) {
- case GPS_DRIVER_MODE_UBX:
- _Helper = new UBX(_serial_fd, &_report);
- break;
- case GPS_DRIVER_MODE_MTK:
- _Helper = new MTK(_serial_fd, &_report);
- break;
- case GPS_DRIVER_MODE_NMEA:
- //_Helper = new NMEA(); //TODO: add NMEA
- break;
- default:
- break;
+ case GPS_DRIVER_MODE_UBX:
+ _Helper = new UBX(_serial_fd, &_report);
+ break;
+
+ case GPS_DRIVER_MODE_MTK:
+ _Helper = new MTK(_serial_fd, &_report);
+ break;
+
+ default:
+ break;
}
+
unlock();
+
if (_Helper->configure(_baudrate) == 0) {
unlock();
@@ -294,6 +296,7 @@ GPS::task_main()
/* opportunistic publishing - else invalid data would end up on the bus */
if (_report_pub > 0) {
orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+
} else {
_report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
}
@@ -310,10 +313,26 @@ GPS::task_main()
}
if (!_healthy) {
- warnx("module found");
+ char *mode_str = "unknown";
+
+ switch (_mode) {
+ case GPS_DRIVER_MODE_UBX:
+ mode_str = "UBX";
+ break;
+
+ case GPS_DRIVER_MODE_MTK:
+ mode_str = "MTK";
+ break;
+
+ default:
+ break;
+ }
+
+ warnx("module found: %s", mode_str);
_healthy = true;
}
}
+
if (_healthy) {
warnx("module lost");
_healthy = false;
@@ -322,25 +341,26 @@ GPS::task_main()
lock();
}
+
lock();
/* select next mode */
switch (_mode) {
- case GPS_DRIVER_MODE_UBX:
- _mode = GPS_DRIVER_MODE_MTK;
- break;
- case GPS_DRIVER_MODE_MTK:
- _mode = GPS_DRIVER_MODE_UBX;
- break;
- // case GPS_DRIVER_MODE_NMEA:
- // _mode = GPS_DRIVER_MODE_UBX;
- // break;
- default:
- break;
+ case GPS_DRIVER_MODE_UBX:
+ _mode = GPS_DRIVER_MODE_MTK;
+ break;
+
+ case GPS_DRIVER_MODE_MTK:
+ _mode = GPS_DRIVER_MODE_UBX;
+ break;
+
+ default:
+ break;
}
}
- debug("exiting");
+
+ warnx("exiting");
::close(_serial_fd);
@@ -361,23 +381,25 @@ void
GPS::print_info()
{
switch (_mode) {
- case GPS_DRIVER_MODE_UBX:
- warnx("protocol: UBX");
- break;
- case GPS_DRIVER_MODE_MTK:
- warnx("protocol: MTK");
- break;
- case GPS_DRIVER_MODE_NMEA:
- warnx("protocol: NMEA");
- break;
- default:
- break;
+ case GPS_DRIVER_MODE_UBX:
+ warnx("protocol: UBX");
+ break;
+
+ case GPS_DRIVER_MODE_MTK:
+ warnx("protocol: MTK");
+ break;
+
+ default:
+ break;
}
+
warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK");
+
if (_report.timestamp_position != 0) {
- warnx("position lock: %dD, last update %4.2f seconds ago", (int)_report.fix_type,
- (double)((float)(hrt_absolute_time() - _report.timestamp_position) / 1000000.0f));
+ warnx("position lock: %dD, satellites: %d, last update: %fms ago", (int)_report.fix_type,
+ _report.satellites_visible, (hrt_absolute_time() - _report.timestamp_position) / 1000.0f);
warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt);
+ warnx("eph: %.2fm, epv: %.2fm", _report.eph_m, _report.epv_m);
warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate());
warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate());
warnx("rate publication:\t%6.2f Hz", (double)_rate);
@@ -428,6 +450,7 @@ start(const char *uart_path)
errx(1, "Could not open device path: %s\n", GPS_DEVICE_PATH);
goto fail;
}
+
exit(0);
fail:
@@ -503,7 +526,7 @@ gps_main(int argc, char *argv[])
{
/* set to default */
- char* device_name = GPS_DEFAULT_UART_PORT;
+ char *device_name = GPS_DEFAULT_UART_PORT;
/*
* Start/load the driver.
@@ -513,15 +536,18 @@ gps_main(int argc, char *argv[])
if (argc > 3) {
if (!strcmp(argv[2], "-d")) {
device_name = argv[3];
+
} else {
goto out;
}
}
+
gps::start(device_name);
}
if (!strcmp(argv[1], "stop"))
gps::stop();
+
/*
* Test the driver/device.
*/
diff --git a/src/drivers/gps/gps_helper.cpp b/src/drivers/gps/gps_helper.cpp
index ba86d370a8..2e2cbc8ddf 100644
--- a/src/drivers/gps/gps_helper.cpp
+++ b/src/drivers/gps/gps_helper.cpp
@@ -87,13 +87,15 @@ GPS_Helper::set_baudrate(const int &fd, unsigned baud)
case 115200: speed = B115200; break;
- warnx("try baudrate: %d\n", speed);
+ warnx("try baudrate: %d\n", speed);
default:
warnx("ERROR: Unsupported baudrate: %d\n", baud);
return -EINVAL;
}
+
struct termios uart_config;
+
int termios_state;
/* fill the struct for the new configuration */
@@ -109,14 +111,17 @@ GPS_Helper::set_baudrate(const int &fd, unsigned baud)
warnx("ERROR setting config: %d (cfsetispeed)\n", termios_state);
return -1;
}
+
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
warnx("ERROR setting config: %d (cfsetospeed)\n", termios_state);
return -1;
}
+
if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
warnx("ERROR setting baudrate (tcsetattr)\n");
return -1;
}
+
/* XXX if resetting the parser here, ensure it does exist (check for null pointer) */
return 0;
}
diff --git a/src/drivers/gps/gps_helper.h b/src/drivers/gps/gps_helper.h
index defc1a074a..73d4b889cb 100644
--- a/src/drivers/gps/gps_helper.h
+++ b/src/drivers/gps/gps_helper.h
@@ -33,7 +33,7 @@
*
****************************************************************************/
-/**
+/**
* @file gps_helper.h
*/
diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp
index 62941d74b3..56b702ea6c 100644
--- a/src/drivers/gps/mtk.cpp
+++ b/src/drivers/gps/mtk.cpp
@@ -48,9 +48,9 @@
MTK::MTK(const int &fd, struct vehicle_gps_position_s *gps_position) :
-_fd(fd),
-_gps_position(gps_position),
-_mtk_revision(0)
+ _fd(fd),
+ _gps_position(gps_position),
+ _mtk_revision(0)
{
decode_init();
}
@@ -73,24 +73,28 @@ MTK::configure(unsigned &baudrate)
warnx("mtk: config write failed");
return -1;
}
+
usleep(10000);
if (strlen(MTK_SET_BINARY) != write(_fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) {
warnx("mtk: config write failed");
return -1;
}
+
usleep(10000);
if (strlen(SBAS_ON) != write(_fd, SBAS_ON, strlen(SBAS_ON))) {
warnx("mtk: config write failed");
return -1;
}
+
usleep(10000);
if (strlen(WAAS_ON) != write(_fd, WAAS_ON, strlen(WAAS_ON))) {
warnx("mtk: config write failed");
return -1;
}
+
usleep(10000);
if (strlen(MTK_NAVTHRES_OFF) != write(_fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) {
@@ -128,12 +132,15 @@ MTK::receive(unsigned timeout)
handle_message(packet);
return 1;
}
+
/* in case we keep trying but only get crap from GPS */
- if (time_started + timeout*1000 < hrt_absolute_time() ) {
+ if (time_started + timeout * 1000 < hrt_absolute_time()) {
return -1;
}
+
j++;
}
+
/* everything is read */
j = count = 0;
}
@@ -181,6 +188,7 @@ MTK::parse_char(uint8_t b, gps_mtk_packet_t &packet)
if (b == MTK_SYNC1_V16) {
_decode_state = MTK_DECODE_GOT_CK_A;
_mtk_revision = 16;
+
} else if (b == MTK_SYNC1_V19) {
_decode_state = MTK_DECODE_GOT_CK_A;
_mtk_revision = 19;
@@ -201,7 +209,7 @@ MTK::parse_char(uint8_t b, gps_mtk_packet_t &packet)
add_byte_to_checksum(b);
// Fill packet buffer
- ((uint8_t*)(&packet))[_rx_count] = b;
+ ((uint8_t *)(&packet))[_rx_count] = b;
_rx_count++;
/* Packet size minus checksum, XXX ? */
@@ -209,14 +217,17 @@ MTK::parse_char(uint8_t b, gps_mtk_packet_t &packet)
/* Compare checksum */
if (_rx_ck_a == packet.ck_a && _rx_ck_b == packet.ck_b) {
ret = 1;
+
} else {
warnx("MTK Checksum invalid");
ret = -1;
}
+
// Reset state machine to decode next packet
decode_init();
}
}
+
return ret;
}
@@ -226,19 +237,22 @@ MTK::handle_message(gps_mtk_packet_t &packet)
if (_mtk_revision == 16) {
_gps_position->lat = packet.latitude * 10; // from degrees*1e6 to degrees*1e7
_gps_position->lon = packet.longitude * 10; // from degrees*1e6 to degrees*1e7
+
} else if (_mtk_revision == 19) {
_gps_position->lat = packet.latitude; // both degrees*1e7
_gps_position->lon = packet.longitude; // both degrees*1e7
+
} else {
warnx("mtk: unknown revision");
_gps_position->lat = 0;
_gps_position->lon = 0;
}
+
_gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm
_gps_position->fix_type = packet.fix_type;
_gps_position->eph_m = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit
_gps_position->epv_m = 0.0; //unknown in mtk custom mode
- _gps_position->vel_m_s = ((float)packet.ground_speed)*1e-2f; // from cm/s to m/s
+ _gps_position->vel_m_s = ((float)packet.ground_speed) * 1e-2f; // from cm/s to m/s
_gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad
_gps_position->satellites_visible = packet.satellites;
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index b579db7150..86291901cb 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -42,13 +42,14 @@
*
* @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
*/
-
-#include
-#include
-#include
-#include
-#include
#include
+#include
+#include
+#include
+#include
+#include
+#include
+
#include
#include
#include
@@ -59,13 +60,14 @@
#define UBX_CONFIG_TIMEOUT 200 // ms, timeout for waiting ACK
#define UBX_PACKET_TIMEOUT 2 // ms, if now data during this delay assume that full update received
#define UBX_WAIT_BEFORE_READ 20 // ms, wait before reading to save read() calls
+#define DISABLE_MSG_INTERVAL 1000000 // us, try to disable message with this interval
UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) :
_fd(fd),
_gps_position(gps_position),
_configured(false),
_waiting_for_ack(false),
- _disable_cmd_counter(0)
+ _disable_cmd_last(0)
{
decode_init();
}
@@ -190,35 +192,35 @@ UBX::configure(unsigned &baudrate)
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_POSLLH, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV POSLLH\n");
+ warnx("ubx: msg rate configuration failed: NAV POSLLH");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV TIMEUTC\n");
+ warnx("ubx: msg rate configuration failed: NAV TIMEUTC");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV SOL\n");
+ warnx("ubx: msg rate configuration failed: NAV SOL");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV VELNED\n");
+ warnx("ubx: msg rate configuration failed: NAV VELNED");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV SVINFO\n");
+ warnx("ubx: msg rate configuration failed: NAV SVINFO");
return 1;
}
@@ -270,11 +272,17 @@ UBX::receive(unsigned timeout)
if (ret < 0) {
/* something went wrong when polling */
+ warnx("ubx: poll error");
return -1;
} else if (ret == 0) {
/* return success after short delay after receiving a packet or timeout after long delay */
- return handled ? 1 : -1;
+ if (handled) {
+ return 1;
+
+ } else {
+ return -1;
+ }
} else if (ret > 0) {
/* if we have new data from GPS, go handle it */
@@ -291,8 +299,6 @@ UBX::receive(unsigned timeout)
/* pass received bytes to the packet decoder */
for (int i = 0; i < count; i++) {
if (parse_char(buf[i]) > 0) {
- /* return to configure during configuration or to the gps driver during normal work
- * if a packet has arrived */
if (handle_message() > 0)
handled = true;
}
@@ -302,6 +308,7 @@ UBX::receive(unsigned timeout)
/* abort after timeout if no useful packets received */
if (time_started + timeout * 1000 < hrt_absolute_time()) {
+ warnx("ubx: timeout - no useful messages");
return -1;
}
}
@@ -453,6 +460,15 @@ UBX::handle_message()
timeinfo.tm_sec = packet->sec;
time_t epoch = mktime(&timeinfo);
+#ifndef CONFIG_RTC
+ //Since we lack a hardware RTC, set the system time clock based on GPS UTC
+ //TODO generalize this by moving into gps.cpp?
+ timespec ts;
+ ts.tv_sec = epoch;
+ ts.tv_nsec = packet->time_nanoseconds;
+ clock_settime(CLOCK_REALTIME, &ts);
+#endif
+
_gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
_gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f);
_gps_position->timestamp_time = hrt_absolute_time();
@@ -554,10 +570,13 @@ UBX::handle_message()
if (ret == 0) {
/* message not handled */
- warnx("ubx: unknown message received: 0x%02x-0x%02x\n", (unsigned)_message_class, (unsigned)_message_id);
+ warnx("ubx: unknown message received: 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id);
- if ((_disable_cmd_counter = _disable_cmd_counter++ % 10) == 0) {
+ hrt_abstime t = hrt_absolute_time();
+
+ if (t > _disable_cmd_last + DISABLE_MSG_INTERVAL) {
/* don't attempt for every message to disable, some might not be disabled */
+ _disable_cmd_last = t;
warnx("ubx: disabling message 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id);
configure_message_rate(_message_class, _message_id, 0);
}
@@ -630,7 +649,7 @@ UBX::add_checksum_to_message(uint8_t *message, const unsigned length)
ck_b = ck_b + ck_a;
}
- /* The checksum is written to the last to bytes of a message */
+ /* the checksum is written to the last to bytes of a message */
message[length - 2] = ck_a;
message[length - 1] = ck_b;
}
@@ -659,17 +678,17 @@ UBX::send_config_packet(const int &fd, uint8_t *packet, const unsigned length)
{
ssize_t ret = 0;
- /* Calculate the checksum now */
+ /* calculate the checksum now */
add_checksum_to_message(packet, length);
const uint8_t sync_bytes[] = {UBX_SYNC1, UBX_SYNC2};
- /* Start with the two sync bytes */
+ /* start with the two sync bytes */
ret += write(fd, sync_bytes, sizeof(sync_bytes));
ret += write(fd, packet, length);
if (ret != (int)length + (int)sizeof(sync_bytes)) // XXX is there a neater way to get rid of the unsigned signed warning?
- warnx("ubx: config write fail");
+ warnx("ubx: configuration write fail");
}
void
@@ -686,7 +705,7 @@ UBX::send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size)
add_checksum((uint8_t *)&header.msg_class, sizeof(header) - 2, ck_a, ck_b);
add_checksum((uint8_t *)msg, size, ck_a, ck_b);
- // Configure receive check
+ /* configure ACK check */
_message_class_needed = msg_class;
_message_id_needed = msg_id;
diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h
index 4fc2769750..76ef873a36 100644
--- a/src/drivers/gps/ubx.h
+++ b/src/drivers/gps/ubx.h
@@ -347,7 +347,7 @@ private:
/**
* Add the two checksum bytes to an outgoing message
*/
- void add_checksum_to_message(uint8_t* message, const unsigned length);
+ void add_checksum_to_message(uint8_t *message, const unsigned length);
/**
* Helper to send a config packet
@@ -358,7 +358,7 @@ private:
void send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size);
- void add_checksum(uint8_t* message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b);
+ void add_checksum(uint8_t *message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b);
int wait_for_ack(unsigned timeout);
@@ -376,7 +376,7 @@ private:
uint8_t _message_class;
uint8_t _message_id;
unsigned _payload_size;
- uint8_t _disable_cmd_counter;
+ uint8_t _disable_cmd_last;
};
#endif /* UBX_H_ */
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index bd027ce0b9..c1d73dd87f 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -75,6 +75,7 @@
#include
#include
+#include
#include
#include
@@ -403,7 +404,7 @@ HIL::task_main()
for (unsigned i = 0; i < num_outputs; i++) {
/* last resort: catch NaN, INF and out-of-band errors */
- if (i < (unsigned)outputs.noutputs &&
+ if (i < outputs.noutputs &&
isfinite(outputs.output[i]) &&
outputs.output[i] >= -1.0f &&
outputs.output[i] <= 1.0f) {
@@ -516,7 +517,7 @@ HIL::pwm_ioctl(file *filp, int cmd, unsigned long arg)
g_hil->set_pwm_rate(arg);
break;
- case PWM_SERVO_SELECT_UPDATE_RATE:
+ case PWM_SERVO_SET_SELECT_UPDATE_RATE:
// HIL always outputs at the alternate (usually faster) rate
break;
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index ac3bdc1325..5f0ce4ff86 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -58,13 +58,14 @@
#include
#include
-#include
+#include
#include
#include
#include
#include