mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Merge branch 'master' into vector_control
This commit is contained in:
commit
e8224376ca
11
.gitignore
vendored
11
.gitignore
vendored
@ -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
|
||||
/Documentation/doxygen*objdb*tmp
|
||||
.tags
|
||||
.tags_sorted_by_file
|
||||
|
||||
@ -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)
|
||||
|
||||
173
Debug/Nuttx.py
173
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()
|
||||
|
||||
@ -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
|
||||
|
||||
13
Debug/dot.gdbinit
Normal file
13
Debug/dot.gdbinit
Normal file
@ -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
|
||||
22
Debug/olimex-px4fmu-debug.cfg
Normal file
22
Debug/olimex-px4fmu-debug.cfg
Normal file
@ -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
|
||||
|
||||
21
Debug/openocd.gdbinit
Normal file
21
Debug/openocd.gdbinit
Normal file
@ -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
|
||||
38
Debug/px4fmu-v1-board.cfg
Normal file
38
Debug/px4fmu-v1-board.cfg
Normal file
@ -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
|
||||
|
||||
5
Debug/runopenocd.sh
Executable file
5
Debug/runopenocd.sh
Executable file
@ -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
|
||||
@ -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
|
||||
File diff suppressed because it is too large
Load Diff
BIN
Documentation/fixed_wing_control.odg
Normal file
BIN
Documentation/fixed_wing_control.odg
Normal file
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
12
Images/px4fmu-v2.prototype
Normal file
12
Images/px4fmu-v2.prototype
Normal file
@ -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
|
||||
}
|
||||
12
Images/px4io-v2.prototype
Normal file
12
Images/px4io-v2.prototype
Normal file
@ -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
|
||||
}
|
||||
12
Images/px4iov2.prototype
Normal file
12
Images/px4iov2.prototype
Normal file
@ -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
|
||||
}
|
||||
66
Makefile
66
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=<list-of-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."
|
||||
|
||||
@ -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
|
||||
@ -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
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
87
ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
Normal file
87
ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
Normal file
@ -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"
|
||||
|
||||
105
ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
Normal file
105
ROMFS/px4fmu_common/init.d/1001_rc_quad.hil
Normal file
@ -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"
|
||||
|
||||
79
ROMFS/px4fmu_common/init.d/1002_rc_fw_state.hil
Normal file
79
ROMFS/px4fmu_common/init.d/1002_rc_fw_state.hil
Normal file
@ -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"
|
||||
|
||||
105
ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
Normal file
105
ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
Normal file
@ -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"
|
||||
|
||||
98
ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil
Normal file
98
ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil
Normal file
@ -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"
|
||||
|
||||
87
ROMFS/px4fmu_common/init.d/100_mpx_easystar
Normal file
87
ROMFS/px4fmu_common/init.d/100_mpx_easystar
Normal file
@ -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
|
||||
87
ROMFS/px4fmu_common/init.d/101_hk_bixler
Normal file
87
ROMFS/px4fmu_common/init.d/101_hk_bixler
Normal file
@ -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
|
||||
97
ROMFS/px4fmu_common/init.d/10_dji_f330
Normal file
97
ROMFS/px4fmu_common/init.d/10_dji_f330
Normal file
@ -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
|
||||
@ -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
|
||||
83
ROMFS/px4fmu_common/init.d/11_dji_f450
Normal file
83
ROMFS/px4fmu_common/init.d/11_dji_f450
Normal file
@ -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
|
||||
98
ROMFS/px4fmu_common/init.d/12-13_hex
Normal file
98
ROMFS/px4fmu_common/init.d/12-13_hex
Normal file
@ -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
|
||||
81
ROMFS/px4fmu_common/init.d/15_tbs_discovery
Normal file
81
ROMFS/px4fmu_common/init.d/15_tbs_discovery
Normal file
@ -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
|
||||
81
ROMFS/px4fmu_common/init.d/16_3dr_iris
Normal file
81
ROMFS/px4fmu_common/init.d/16_3dr_iris
Normal file
@ -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
|
||||
@ -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
|
||||
@ -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
|
||||
65
ROMFS/px4fmu_common/init.d/32_skywalker_x5
Normal file
65
ROMFS/px4fmu_common/init.d/32_skywalker_x5
Normal file
@ -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
|
||||
@ -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
|
||||
|
||||
83
ROMFS/px4fmu_common/init.d/666_fmu_q_x550
Normal file
83
ROMFS/px4fmu_common/init.d/666_fmu_q_x550
Normal file
@ -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
|
||||
9
ROMFS/px4fmu_common/init.d/cmp_test
Normal file
9
ROMFS/px4fmu_common/init.d/cmp_test
Normal file
@ -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
|
||||
@ -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
|
||||
120
ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
Normal file
120
ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
Normal file
@ -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
|
||||
120
ROMFS/px4fmu_common/init.d/rc.custom_io_esc
Normal file
120
ROMFS/px4fmu_common/init.d/rc.custom_io_esc
Normal file
@ -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"
|
||||
34
ROMFS/px4fmu_common/init.d/rc.fixedwing
Normal file
34
ROMFS/px4fmu_common/init.d/rc.fixedwing
Normal file
@ -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
|
||||
@ -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
|
||||
23
ROMFS/px4fmu_common/init.d/rc.io
Normal file
23
ROMFS/px4fmu_common/init.d/rc.io
Normal file
@ -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
|
||||
@ -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
|
||||
|
||||
39
ROMFS/px4fmu_common/init.d/rc.multirotor
Normal file
39
ROMFS/px4fmu_common/init.d/rc.multirotor
Normal file
@ -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
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
|
||||
@ -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
|
||||
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
7
ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix
Normal file
7
ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix
Normal file
@ -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
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
13
ROMFS/px4fmu_test/init.d/rc.standalone
Normal file
13
ROMFS/px4fmu_test/init.d/rc.standalone
Normal file
@ -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"
|
||||
4
ROMFS/px4fmu_test/init.d/rcS
Executable file
4
ROMFS/px4fmu_test/init.d/rcS
Executable file
@ -0,0 +1,4 @@
|
||||
#!nsh
|
||||
#
|
||||
# PX4FMU startup script for test hackery.
|
||||
#
|
||||
2
Tools/px4params/.gitignore
vendored
Normal file
2
Tools/px4params/.gitignore
vendored
Normal file
@ -0,0 +1,2 @@
|
||||
parameters.wiki
|
||||
parameters.xml
|
||||
9
Tools/px4params/README.md
Normal file
9
Tools/px4params/README.md
Normal file
@ -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
|
||||
27
Tools/px4params/dokuwikiout.py
Normal file
27
Tools/px4params/dokuwikiout.py
Normal file
@ -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
|
||||
5
Tools/px4params/output.py
Normal file
5
Tools/px4params/output.py
Normal file
@ -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)
|
||||
220
Tools/px4params/parser.py
Normal file
220
Tools/px4params/parser.py
Normal file
@ -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()))
|
||||
61
Tools/px4params/px_process_params.py
Executable file
61
Tools/px4params/px_process_params.py
Executable file
@ -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")
|
||||
34
Tools/px4params/scanner.py
Normal file
34
Tools/px4params/scanner.py
Normal file
@ -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)
|
||||
22
Tools/px4params/xmlout.py
Normal file
22
Tools/px4params/xmlout.py
Normal file
@ -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")
|
||||
@ -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))
|
||||
|
||||
@ -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:
|
||||
|
||||
@ -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
|
||||
|
||||
2
Tools/tests-host/.gitignore
vendored
Normal file
2
Tools/tests-host/.gitignore
vendored
Normal file
@ -0,0 +1,2 @@
|
||||
./obj/*
|
||||
mixer_test
|
||||
39
Tools/tests-host/Makefile
Normal file
39
Tools/tests-host/Makefile
Normal file
@ -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)/*~
|
||||
0
Tools/tests-host/arch/board/board.h
Normal file
0
Tools/tests-host/arch/board/board.h
Normal file
12
Tools/tests-host/mixer_test.cpp
Normal file
12
Tools/tests-host/mixer_test.cpp
Normal file
@ -0,0 +1,12 @@
|
||||
#include <systemlib/mixer/mixer.h>
|
||||
#include <systemlib/err.h>
|
||||
#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);
|
||||
}
|
||||
0
Tools/tests-host/nuttx/config.h
Normal file
0
Tools/tests-host/nuttx/config.h
Normal file
11
makefiles/board_px4fmu-v2.mk
Normal file
11
makefiles/board_px4fmu-v2.mk
Normal file
@ -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
|
||||
11
makefiles/board_px4io-v2.mk
Normal file
11
makefiles/board_px4io-v2.mk
Normal file
@ -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
|
||||
@ -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.
|
||||
|
||||
155
makefiles/config_px4fmu-v2_default.mk
Normal file
155
makefiles/config_px4fmu-v2_default.mk
Normal file
@ -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 <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
|
||||
# to make the table a bit more readable.
|
||||
#
|
||||
define _B
|
||||
$(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
|
||||
endef
|
||||
|
||||
# command priority stack entrypoint
|
||||
BUILTIN_COMMANDS := \
|
||||
$(call _B, sercon, , 2048, sercon_main ) \
|
||||
$(call _B, serdis, , 2048, serdis_main )
|
||||
41
makefiles/config_px4fmu-v2_test.mk
Normal file
41
makefiles/config_px4fmu-v2_test.mk
Normal file
@ -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 <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
|
||||
# to make the table a bit more readable.
|
||||
#
|
||||
define _B
|
||||
$(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
|
||||
endef
|
||||
|
||||
# command priority stack entrypoint
|
||||
BUILTIN_COMMANDS := \
|
||||
$(call _B, sercon, , 2048, sercon_main ) \
|
||||
$(call _B, serdis, , 2048, serdis_main )
|
||||
@ -6,5 +6,5 @@
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/stm32
|
||||
MODULES += drivers/boards/px4io
|
||||
MODULES += drivers/boards/px4io-v1
|
||||
MODULES += modules/px4iofirmware
|
||||
10
makefiles/config_px4io-v2_default.mk
Normal file
10
makefiles/config_px4io-v2_default.mk
Normal file
@ -0,0 +1,10 @@
|
||||
#
|
||||
# Makefile for the px4iov2_default configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/stm32
|
||||
MODULES += drivers/boards/px4io-v2
|
||||
MODULES += modules/px4iofirmware
|
||||
@ -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)
|
||||
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
File diff suppressed because one or more lines are too long
@ -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
|
||||
|
||||
@ -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
|
||||
}
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user