mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-03 01:40:04 +08:00
Compare commits
2 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| d5d09bab84 | |||
| d9e33b68cf |
@@ -70,12 +70,16 @@ pipeline {
|
||||
"omnibus_f4sd_default",
|
||||
"px4_fmu-v2_default",
|
||||
"px4_fmu-v2_fixedwing",
|
||||
"px4_fmu-v2_lpe",
|
||||
"px4_fmu-v2_multicopter",
|
||||
"px4_fmu-v2_rover",
|
||||
"px4_fmu-v2_test",
|
||||
"px4_fmu-v3_ctrlalloc",
|
||||
"px4_fmu-v3_default",
|
||||
"px4_fmu-v4_cannode",
|
||||
"px4_fmu-v4_ctrlalloc",
|
||||
"px4_fmu-v4_default",
|
||||
"px4_fmu-v4_optimized",
|
||||
"px4_fmu-v4pro_default",
|
||||
"px4_fmu-v5_ctrlalloc",
|
||||
"px4_fmu-v5_debug",
|
||||
|
||||
@@ -52,8 +52,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
- name: check environment
|
||||
|
||||
@@ -34,8 +34,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
|
||||
@@ -43,8 +43,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
|
||||
@@ -39,8 +39,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
|
||||
@@ -43,8 +43,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
|
||||
@@ -49,12 +49,16 @@ jobs:
|
||||
omnibus_f4sd_default,
|
||||
px4_fmu-v2_default,
|
||||
px4_fmu-v2_fixedwing,
|
||||
px4_fmu-v2_lpe,
|
||||
px4_fmu-v2_multicopter,
|
||||
px4_fmu-v2_rover,
|
||||
px4_fmu-v2_test,
|
||||
px4_fmu-v3_ctrlalloc,
|
||||
px4_fmu-v3_default,
|
||||
px4_fmu-v4_cannode,
|
||||
px4_fmu-v4_ctrlalloc,
|
||||
px4_fmu-v4_default,
|
||||
px4_fmu-v4_optimized,
|
||||
px4_fmu-v4pro_default,
|
||||
px4_fmu-v5_ctrlalloc,
|
||||
px4_fmu-v5_default,
|
||||
@@ -63,6 +67,7 @@ jobs:
|
||||
px4_fmu-v5_optimized,
|
||||
px4_fmu-v5_rover,
|
||||
px4_fmu-v5_rtps,
|
||||
px4_fmu-v5_stackcheck,
|
||||
px4_fmu-v5_uavcanv0periph,
|
||||
px4_fmu-v5_uavcanv1,
|
||||
px4_fmu-v5x_base_phy_DP83848C,
|
||||
@@ -95,8 +100,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
|
||||
@@ -43,8 +43,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
|
||||
@@ -43,8 +43,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
|
||||
@@ -49,8 +49,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
|
||||
@@ -44,8 +44,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
|
||||
@@ -49,8 +49,8 @@ jobs:
|
||||
mkdir -p ~/.ccache
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 5" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 100M" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 400M" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
|
||||
@@ -42,7 +42,6 @@ px4_add_romfs_files(
|
||||
rc.fw_apps
|
||||
rc.fw_defaults
|
||||
rc.interface
|
||||
rc.io
|
||||
rc.logging
|
||||
rc.mc_apps
|
||||
rc.mc_defaults
|
||||
|
||||
@@ -49,7 +49,6 @@ param set-default CBRK_IO_SAFETY 22027
|
||||
param set-default CBRK_SUPPLY_CHK 894281
|
||||
|
||||
# RC configuration
|
||||
param set-default RC_MAP_MODE_SW 5
|
||||
param set-default RC_MAP_PITCH 2
|
||||
param set-default RC_MAP_ROLL 1
|
||||
param set-default RC_MAP_THROTTLE 3
|
||||
|
||||
@@ -93,19 +93,15 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE = io ]
|
||||
then
|
||||
. ${R}etc/init.d/rc.io
|
||||
fi
|
||||
|
||||
#
|
||||
# Start IO for RC input if needed.
|
||||
#
|
||||
if [ $IO_PRESENT = yes ]
|
||||
if [ $IO_PRESENT = yes -a $OUTPUT_MODE = io ]
|
||||
then
|
||||
if [ $OUTPUT_MODE != io ]
|
||||
if ! px4io start
|
||||
then
|
||||
. ${R}etc/init.d/rc.io
|
||||
echo "PX4IO start failed"
|
||||
tune_control play -t 18 # PROG_PX4IO_ERR
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
@@ -1,23 +0,0 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# PX4IO interface init script.
|
||||
#
|
||||
|
||||
# If $OUTPUT_MODE indicated Hardware-int-the-loop simulation, px4io should not publish actuator_outputs,
|
||||
# instead, pwm_out_sim will publish that uORB
|
||||
if [ $OUTPUT_MODE = hil ]
|
||||
then
|
||||
set HIL_ARG $OUTPUT_MODE
|
||||
fi
|
||||
|
||||
if [ $IO_PRESENT = yes ]
|
||||
then
|
||||
if px4io start $HIL_ARG
|
||||
then
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
px4io recovery
|
||||
else
|
||||
echo "PX4IO start failed"
|
||||
tune_control play -t 18 # PROG_PX4IO_ERR
|
||||
fi
|
||||
fi
|
||||
@@ -382,25 +382,23 @@ else
|
||||
|
||||
if param greater -s TRIG_MODE 0
|
||||
then
|
||||
# # We ONLY support trigger on pins 5+6 or 7+8 when simultanously using AUX for actuator output.
|
||||
# if param compare TRIG_PINS 56
|
||||
# then
|
||||
# # clear pins 5 and 6
|
||||
# set FMU_MODE pwm4
|
||||
# set AUX_MODE pwm4
|
||||
# else
|
||||
# if param compare TRIG_PINS 78
|
||||
# then
|
||||
# # clear pins 7 and 8
|
||||
# set FMU_MODE pwm6
|
||||
# set AUX_MODE pwm6
|
||||
# else
|
||||
# set FMU_MODE none
|
||||
# set AUX_MODE none
|
||||
# fi
|
||||
# fi
|
||||
|
||||
set FMU_MODE pwm12
|
||||
# We ONLY support trigger on pins 5+6 or 7+8 when simultanously using AUX for actuator output.
|
||||
if param compare TRIG_PINS 56
|
||||
then
|
||||
# clear pins 5 and 6
|
||||
set FMU_MODE pwm4
|
||||
set AUX_MODE pwm4
|
||||
else
|
||||
if param compare TRIG_PINS 78
|
||||
then
|
||||
# clear pins 7 and 8
|
||||
set FMU_MODE pwm6
|
||||
set AUX_MODE pwm6
|
||||
else
|
||||
set FMU_MODE none
|
||||
set AUX_MODE none
|
||||
fi
|
||||
fi
|
||||
|
||||
camera_trigger start
|
||||
camera_feedback start
|
||||
|
||||
@@ -53,7 +53,6 @@
|
||||
#include <fcntl.h>
|
||||
#include <mqueue.h>
|
||||
|
||||
#include <drivers/drv_rc_input.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
@@ -96,7 +95,7 @@ Syslink::Syslink() :
|
||||
_fd(0),
|
||||
_queue(2, sizeof(syslink_message_t)),
|
||||
_writebuffer(16, sizeof(crtp_message_t)),
|
||||
_rssi(RC_INPUT_RSSI_MAX),
|
||||
_rssi(input_rc_s::RSSI_MAX),
|
||||
_bstate(BAT_DISCHARGING)
|
||||
{
|
||||
px4_sem_init(&memory_sem, 0, 0);
|
||||
|
||||
@@ -31,7 +31,7 @@ px4_add_board(
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/bosch/bmi088
|
||||
#imu/invensense/icm20649
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
|
||||
@@ -16,7 +16,7 @@ bmi088 -s -b 4 -G -R 2 start
|
||||
ms5611 -s -b 4 start
|
||||
|
||||
# SPI6
|
||||
#icm20649 -s -b 6 -R 2 start # TODO: not started by default until NuttX SPI6 BDMA is fixed
|
||||
icm20649 -s -b 6 -R 2 start
|
||||
ms5611 -s -b 6 start
|
||||
|
||||
# External compass on GPS1/I2C1: standard CUAV GPS/compass puck (with lights, safety button, and buzzer)
|
||||
|
||||
@@ -43,4 +43,3 @@ param set-default UAVCAN_ENABLE 2
|
||||
|
||||
|
||||
set LOGGER_BUF 64
|
||||
set IOFW "/etc/extras/cubepilot_io-v2_default.bin"
|
||||
|
||||
@@ -46,6 +46,7 @@
|
||||
|
||||
/* PX4IO connection configuration */
|
||||
#define BOARD_USES_PX4IO_VERSION 2
|
||||
#define BOARD_PX4IO_FW_SEARCH_PATHS {"/etc/extras/cubepilot_io-v2_default.bin","/fs/microsd/cubepilot_io-v2_default.bin", nullptr }
|
||||
#define PX4IO_SERIAL_DEVICE "/dev/ttyS3"
|
||||
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
|
||||
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
|
||||
|
||||
@@ -23,4 +23,3 @@ param set-default UAVCAN_ENABLE 2
|
||||
|
||||
|
||||
set LOGGER_BUF 64
|
||||
set IOFW "/etc/extras/cubepilot_io-v2_default.bin"
|
||||
|
||||
@@ -46,6 +46,7 @@
|
||||
|
||||
/* PX4IO connection configuration */
|
||||
#define BOARD_USES_PX4IO_VERSION 2
|
||||
#define BOARD_PX4IO_FW_SEARCH_PATHS {"/etc/extras/cubepilot_io-v2_default.bin","/fs/microsd/cubepilot_io-v2_default.bin", nullptr }
|
||||
#define PX4IO_SERIAL_DEVICE "/dev/ttyS3"
|
||||
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
|
||||
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
|
||||
|
||||
@@ -0,0 +1,242 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743II=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_STACKCHECK=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x004b
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 DurandalV1"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x3162
|
||||
CONFIG_CDCACM_VENDORSTR="Holybro"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_MEMFAULT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
CONFIG_MM_REGIONS=3
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_PROGMEM=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_IFCONFIG=y
|
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDMMC1_SDIO_MODE=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=256
|
||||
CONFIG_STM32H7_ADC1=y
|
||||
CONFIG_STM32H7_BBSRAM=y
|
||||
CONFIG_STM32H7_BBSRAM_FILES=5
|
||||
CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_DTCMEXCLUDE=y
|
||||
CONFIG_STM32H7_DTCM_PROCFS=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C2=y
|
||||
CONFIG_STM32H7_I2C3=y
|
||||
CONFIG_STM32H7_I2C4=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC1=y
|
||||
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_SPI1=y
|
||||
CONFIG_STM32H7_SPI1_DMA=y
|
||||
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI4=y
|
||||
CONFIG_STM32H7_SPI5=y
|
||||
CONFIG_STM32H7_SPI6=y
|
||||
CONFIG_STM32H7_SPI6_DMA=y
|
||||
CONFIG_STM32H7_SPI6_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI_DMA=y
|
||||
CONFIG_STM32H7_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM3=y
|
||||
CONFIG_STM32H7_TIM4=y
|
||||
CONFIG_STM32H7_UART4=y
|
||||
CONFIG_STM32H7_UART7=y
|
||||
CONFIG_STM32H7_UART8=y
|
||||
CONFIG_STM32H7_USART1=y
|
||||
CONFIG_STM32H7_USART2=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_USART6=y
|
||||
CONFIG_STM32H7_USART_BREAKS=y
|
||||
CONFIG_STM32H7_USART_INVERT=y
|
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32H7_USART_SWAP=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TTY_SIGINT=y
|
||||
CONFIG_TTY_SIGSTP=y
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_SERIAL_CONSOLE=y
|
||||
CONFIG_UART7_TXBUFSIZE=1500
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=600
|
||||
CONFIG_UART8_TXBUFSIZE=1500
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_TXBUFSIZE=1500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_TXBUFSIZE=1500
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_TXBUFSIZE=3000
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
@@ -0,0 +1,104 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR intel
|
||||
MODEL aerofc-v1
|
||||
LABEL rtps
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
ROMFSROOT px4fmu_common
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS5
|
||||
TEL1:/dev/ttyS3
|
||||
TEL2:/dev/ttyS1
|
||||
DRIVERS
|
||||
barometer/ms5611
|
||||
#camera_trigger
|
||||
#differential_pressure # all available differential pressure drivers
|
||||
distance_sensor
|
||||
gps
|
||||
imu/invensense/mpu9250
|
||||
#irlock
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
magnetometer/isentek/ist8310
|
||||
#optical_flow/px4flow
|
||||
protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
tap_esc
|
||||
#telemetry # all available telemetry drivers
|
||||
#uavcan
|
||||
MODULES
|
||||
#airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
#camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
#fw_att_control
|
||||
#fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
#rover_pos_control
|
||||
sensors
|
||||
#sih
|
||||
#temperature_compensation
|
||||
vmount
|
||||
#vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
#tests # tests and test runner
|
||||
top
|
||||
#topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
#fake_gps
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#uuv_example_app
|
||||
#work_item
|
||||
)
|
||||
@@ -0,0 +1,123 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v2
|
||||
LABEL lpe
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
ROMFSROOT px4fmu_common
|
||||
BOOTLOADER ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/extras/px4fmuv3_bl.bin
|
||||
IO px4_io-v2_default
|
||||
#TESTING
|
||||
CONSTRAINED_FLASH
|
||||
#UAVCAN_INTERFACES 2
|
||||
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS6
|
||||
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/ms5611
|
||||
#batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
#differential_pressure # all available differential pressure drivers
|
||||
#differential_pressure/ms4525
|
||||
distance_sensor # all available distance sensor drivers
|
||||
gps
|
||||
#heater
|
||||
#imu/analog_devices/adis16448
|
||||
#imu # all available imu drivers
|
||||
imu/l3gd20
|
||||
imu/lsm303d
|
||||
imu/invensense/mpu6000
|
||||
#iridiumsbd
|
||||
irlock
|
||||
#lights/blinkm
|
||||
lights/rgbled
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#pca9685
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
#tap_esc
|
||||
#telemetry # all available telemetry drivers
|
||||
#test_ppm
|
||||
tone_alarm
|
||||
#uavcan
|
||||
|
||||
MODULES
|
||||
attitude_estimator_q
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
#ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
#fw_att_control
|
||||
#fw_pos_control_l1
|
||||
#rover_pos_control
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_rate_control
|
||||
mc_pos_control
|
||||
navigator
|
||||
battery_status
|
||||
rc_update
|
||||
sensors
|
||||
temperature_compensation
|
||||
#vmount
|
||||
#vtol_att_control
|
||||
#airspeed_selector
|
||||
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dumpfile
|
||||
#esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
#led_control
|
||||
mft
|
||||
mixer
|
||||
#motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
#nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
#sd_bench
|
||||
#tests # tests and test runner
|
||||
top
|
||||
#topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
ver
|
||||
work_queue
|
||||
|
||||
EXAMPLES
|
||||
#fake_gps
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
)
|
||||
@@ -0,0 +1,140 @@
|
||||
|
||||
# FMUv3 is FMUv2 with access to the full 2MB flash
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v3
|
||||
LABEL ctrlalloc
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
ROMFSROOT px4fmu_common
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/l3gd20
|
||||
imu/lsm303d
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/icm20948
|
||||
imu/invensense/mpu6000
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
#power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
angular_velocity_controller
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
control_allocator
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -0,0 +1,238 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
# CONFIG_STM32_CCMEXCLUDE is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARCH_CHIP_STM32=y
|
||||
CONFIG_ARCH_CHIP_STM32F427V=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_STACKCHECK=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0011
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v2.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=2000
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_VENDORSTR="3D Robotics"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_DISABLE_MQUEUE=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_IFCONFIG=y
|
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDIO_BLOCKSETUP=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_STM32_ADC1=y
|
||||
CONFIG_STM32_BBSRAM=y
|
||||
CONFIG_STM32_BBSRAM_FILES=5
|
||||
CONFIG_STM32_BKPSRAM=y
|
||||
CONFIG_STM32_CCMDATARAM=y
|
||||
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
|
||||
CONFIG_STM32_DMA1=y
|
||||
CONFIG_STM32_DMA2=y
|
||||
CONFIG_STM32_FLASH_CONFIG_I=y
|
||||
CONFIG_STM32_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32_I2C1=y
|
||||
CONFIG_STM32_I2C2=y
|
||||
CONFIG_STM32_I2CTIMEOMS=10
|
||||
CONFIG_STM32_I2CTIMEOTICKS=10
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_OTGFS=y
|
||||
CONFIG_STM32_PWR=y
|
||||
CONFIG_STM32_RTC=y
|
||||
CONFIG_STM32_RTC_HSECLOCK=y
|
||||
CONFIG_STM32_RTC_MAGIC=0xfacefeee
|
||||
CONFIG_STM32_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
|
||||
CONFIG_STM32_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32_SDIO=y
|
||||
CONFIG_STM32_SDIO_CARD=y
|
||||
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_SPI1=y
|
||||
CONFIG_STM32_SPI1_DMA=y
|
||||
CONFIG_STM32_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32_SPI2=y
|
||||
CONFIG_STM32_SPI4=y
|
||||
CONFIG_STM32_SPI4_DMA=y
|
||||
CONFIG_STM32_SPI4_DMA_BUFFER=1024
|
||||
CONFIG_STM32_SPI_DMA=y
|
||||
CONFIG_STM32_SPI_DMATHRESHOLD=32
|
||||
CONFIG_STM32_TIM10=y
|
||||
CONFIG_STM32_TIM11=y
|
||||
CONFIG_STM32_TIM3=y
|
||||
CONFIG_STM32_TIM9=y
|
||||
CONFIG_STM32_UART4=y
|
||||
CONFIG_STM32_UART7=y
|
||||
CONFIG_STM32_UART8=y
|
||||
CONFIG_STM32_USART1=y
|
||||
CONFIG_STM32_USART2=y
|
||||
CONFIG_STM32_USART3=y
|
||||
CONFIG_STM32_USART6=y
|
||||
CONFIG_STM32_USART_BREAKS=y
|
||||
CONFIG_STM32_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32_WWDG=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=300
|
||||
CONFIG_UART4_RXDMA=y
|
||||
CONFIG_UART4_TXBUFSIZE=300
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=300
|
||||
CONFIG_UART7_RXDMA=y
|
||||
CONFIG_UART7_SERIAL_CONSOLE=y
|
||||
CONFIG_UART7_TXBUFSIZE=300
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=300
|
||||
CONFIG_UART8_TXBUFSIZE=300
|
||||
CONFIG_USART1_RXBUFSIZE=128
|
||||
CONFIG_USART1_TXBUFSIZE=32
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_RXDMA=y
|
||||
CONFIG_USART2_TXBUFSIZE=1100
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=300
|
||||
CONFIG_USART3_RXDMA=y
|
||||
CONFIG_USART3_TXBUFSIZE=600
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=300
|
||||
CONFIG_USART6_RXDMA=y
|
||||
CONFIG_USART6_TXBUFSIZE=300
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
@@ -0,0 +1,134 @@
|
||||
|
||||
# FMUv3 is FMUv2 with access to the full 2MB flash
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v3
|
||||
LABEL rtps
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
ROMFSROOT px4fmu_common
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/l3gd20
|
||||
imu/lsm303d
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/icm20948
|
||||
imu/invensense/mpu6000
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
pca9685
|
||||
#power_monitor/ina226
|
||||
protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -0,0 +1,130 @@
|
||||
|
||||
# FMUv3 is FMUv2 with access to the full 2MB flash
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v3
|
||||
LABEL stackcheck
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
ROMFSROOT px4fmu_common
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
#UAVCAN_INTERFACES 2
|
||||
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS3
|
||||
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
gps
|
||||
#heater
|
||||
imu/analog_devices/adis16448
|
||||
#imu # all available imu drivers
|
||||
imu/l3gd20
|
||||
imu/lsm303d
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/mpu6000
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
pca9685
|
||||
protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
#uavcan
|
||||
|
||||
MODULES
|
||||
attitude_estimator_q
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
rover_pos_control
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_rate_control
|
||||
mc_pos_control
|
||||
navigator
|
||||
battery_status
|
||||
rc_update
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
airspeed_selector
|
||||
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
|
||||
EXAMPLES
|
||||
#fake_gps
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#uuv_example_app
|
||||
|
||||
)
|
||||
@@ -0,0 +1,140 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v4
|
||||
LABEL ctrlalloc
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
ROMFSROOT px4fmu_common
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 1
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
WIFI:/dev/ttyS0
|
||||
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/icm40609d
|
||||
imu/invensense/mpu6500
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
angular_velocity_controller
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
control_allocator
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
gyro_fft
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -0,0 +1,236 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
# CONFIG_STM32_CCMEXCLUDE is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARCH_CHIP_STM32=y
|
||||
CONFIG_ARCH_CHIP_STM32F427V=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0012
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v4.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=2000
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_VENDORSTR="3D Robotics"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_CUSTOMOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_OPTLEVEL="-O3"
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_DISABLE_MQUEUE=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_IFCONFIG=y
|
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDIO_BLOCKSETUP=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_STM32_ADC1=y
|
||||
CONFIG_STM32_BBSRAM=y
|
||||
CONFIG_STM32_BBSRAM_FILES=5
|
||||
CONFIG_STM32_BKPSRAM=y
|
||||
CONFIG_STM32_CCMDATARAM=y
|
||||
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
|
||||
CONFIG_STM32_DMA1=y
|
||||
CONFIG_STM32_DMA2=y
|
||||
CONFIG_STM32_FLASH_CONFIG_I=y
|
||||
CONFIG_STM32_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32_I2C1=y
|
||||
CONFIG_STM32_I2CTIMEOMS=10
|
||||
CONFIG_STM32_I2CTIMEOTICKS=10
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_OTGFS=y
|
||||
CONFIG_STM32_PWR=y
|
||||
CONFIG_STM32_RTC=y
|
||||
CONFIG_STM32_RTC_HSECLOCK=y
|
||||
CONFIG_STM32_RTC_MAGIC=0xfacefeee
|
||||
CONFIG_STM32_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
|
||||
CONFIG_STM32_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32_SDIO=y
|
||||
CONFIG_STM32_SDIO_CARD=y
|
||||
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_SPI1=y
|
||||
CONFIG_STM32_SPI1_DMA=y
|
||||
CONFIG_STM32_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32_SPI2=y
|
||||
CONFIG_STM32_SPI4=y
|
||||
CONFIG_STM32_SPI_DMA=y
|
||||
CONFIG_STM32_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32_TIM10=y
|
||||
CONFIG_STM32_TIM11=y
|
||||
CONFIG_STM32_TIM8=y
|
||||
CONFIG_STM32_TIM9=y
|
||||
CONFIG_STM32_UART4=y
|
||||
CONFIG_STM32_UART7=y
|
||||
CONFIG_STM32_UART8=y
|
||||
CONFIG_STM32_USART1=y
|
||||
CONFIG_STM32_USART2=y
|
||||
CONFIG_STM32_USART3=y
|
||||
CONFIG_STM32_USART6=y
|
||||
CONFIG_STM32_USART_BREAKS=y
|
||||
CONFIG_STM32_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32_WWDG=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=300
|
||||
CONFIG_UART4_RXDMA=y
|
||||
CONFIG_UART4_TXBUFSIZE=300
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=300
|
||||
CONFIG_UART7_RXDMA=y
|
||||
CONFIG_UART7_SERIAL_CONSOLE=y
|
||||
CONFIG_UART7_TXBUFSIZE=300
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=300
|
||||
CONFIG_UART8_TXBUFSIZE=300
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_RXDMA=y
|
||||
CONFIG_USART1_TXBUFSIZE=2500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_RXDMA=y
|
||||
CONFIG_USART2_TXBUFSIZE=1100
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=1200
|
||||
CONFIG_USART3_RXDMA=y
|
||||
CONFIG_USART3_TXBUFSIZE=900
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=300
|
||||
CONFIG_USART6_RXDMA=y
|
||||
CONFIG_USART6_TXBUFSIZE=300
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
@@ -0,0 +1,236 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
# CONFIG_STM32_CCMEXCLUDE is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARCH_CHIP_STM32=y
|
||||
CONFIG_ARCH_CHIP_STM32F427V=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_STACKCHECK=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0012
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v4.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=2000
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_VENDORSTR="3D Robotics"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_DISABLE_MQUEUE=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_IFCONFIG=y
|
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDIO_BLOCKSETUP=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_STM32_ADC1=y
|
||||
CONFIG_STM32_BBSRAM=y
|
||||
CONFIG_STM32_BBSRAM_FILES=5
|
||||
CONFIG_STM32_BKPSRAM=y
|
||||
CONFIG_STM32_CCMDATARAM=y
|
||||
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
|
||||
CONFIG_STM32_DMA1=y
|
||||
CONFIG_STM32_DMA2=y
|
||||
CONFIG_STM32_FLASH_CONFIG_I=y
|
||||
CONFIG_STM32_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32_I2C1=y
|
||||
CONFIG_STM32_I2CTIMEOMS=10
|
||||
CONFIG_STM32_I2CTIMEOTICKS=10
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_OTGFS=y
|
||||
CONFIG_STM32_PWR=y
|
||||
CONFIG_STM32_RTC=y
|
||||
CONFIG_STM32_RTC_HSECLOCK=y
|
||||
CONFIG_STM32_RTC_MAGIC=0xfacefeee
|
||||
CONFIG_STM32_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
|
||||
CONFIG_STM32_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32_SDIO=y
|
||||
CONFIG_STM32_SDIO_CARD=y
|
||||
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_SPI1=y
|
||||
CONFIG_STM32_SPI1_DMA=y
|
||||
CONFIG_STM32_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32_SPI2=y
|
||||
CONFIG_STM32_SPI4=y
|
||||
CONFIG_STM32_SPI_DMA=y
|
||||
CONFIG_STM32_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32_TIM10=y
|
||||
CONFIG_STM32_TIM11=y
|
||||
CONFIG_STM32_TIM8=y
|
||||
CONFIG_STM32_TIM9=y
|
||||
CONFIG_STM32_UART4=y
|
||||
CONFIG_STM32_UART7=y
|
||||
CONFIG_STM32_UART8=y
|
||||
CONFIG_STM32_USART1=y
|
||||
CONFIG_STM32_USART2=y
|
||||
CONFIG_STM32_USART3=y
|
||||
CONFIG_STM32_USART6=y
|
||||
CONFIG_STM32_USART_BREAKS=y
|
||||
CONFIG_STM32_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32_WWDG=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=300
|
||||
CONFIG_UART4_RXDMA=y
|
||||
CONFIG_UART4_TXBUFSIZE=300
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=300
|
||||
CONFIG_UART7_RXDMA=y
|
||||
CONFIG_UART7_SERIAL_CONSOLE=y
|
||||
CONFIG_UART7_TXBUFSIZE=300
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=300
|
||||
CONFIG_UART8_TXBUFSIZE=300
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_RXDMA=y
|
||||
CONFIG_USART1_TXBUFSIZE=2500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_RXDMA=y
|
||||
CONFIG_USART2_TXBUFSIZE=1100
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=1200
|
||||
CONFIG_USART3_RXDMA=y
|
||||
CONFIG_USART3_TXBUFSIZE=900
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=300
|
||||
CONFIG_USART6_RXDMA=y
|
||||
CONFIG_USART6_TXBUFSIZE=300
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
@@ -0,0 +1,239 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
# CONFIG_STM32_CCMEXCLUDE is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARCH_CHIP_STM32=y
|
||||
CONFIG_ARCH_CHIP_STM32F427V=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_LAZYFPU=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CAN_EXTID=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0012
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v4.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=2000
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_VENDORSTR="3D Robotics"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_DISABLE_MQUEUE=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_IFCONFIG=y
|
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x20000000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDIO_BLOCKSETUP=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_STM32_ADC1=y
|
||||
CONFIG_STM32_BBSRAM=y
|
||||
CONFIG_STM32_BBSRAM_FILES=5
|
||||
CONFIG_STM32_BKPSRAM=y
|
||||
CONFIG_STM32_CAN1=y
|
||||
CONFIG_STM32_CAN1_BAUD=1000000
|
||||
CONFIG_STM32_CCMDATARAM=y
|
||||
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
|
||||
CONFIG_STM32_DMA1=y
|
||||
CONFIG_STM32_DMA2=y
|
||||
CONFIG_STM32_FLASH_CONFIG_I=y
|
||||
CONFIG_STM32_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32_I2C1=y
|
||||
CONFIG_STM32_I2CTIMEOMS=10
|
||||
CONFIG_STM32_I2CTIMEOTICKS=10
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_OTGFS=y
|
||||
CONFIG_STM32_PWR=y
|
||||
CONFIG_STM32_RTC=y
|
||||
CONFIG_STM32_RTC_HSECLOCK=y
|
||||
CONFIG_STM32_RTC_MAGIC=0xfacefeee
|
||||
CONFIG_STM32_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef
|
||||
CONFIG_STM32_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32_SDIO=y
|
||||
CONFIG_STM32_SDIO_CARD=y
|
||||
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_SPI1=y
|
||||
CONFIG_STM32_SPI1_DMA=y
|
||||
CONFIG_STM32_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32_SPI2=y
|
||||
CONFIG_STM32_SPI4=y
|
||||
CONFIG_STM32_SPI_DMA=y
|
||||
CONFIG_STM32_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32_TIM10=y
|
||||
CONFIG_STM32_TIM11=y
|
||||
CONFIG_STM32_TIM8=y
|
||||
CONFIG_STM32_TIM9=y
|
||||
CONFIG_STM32_UART4=y
|
||||
CONFIG_STM32_UART7=y
|
||||
CONFIG_STM32_UART8=y
|
||||
CONFIG_STM32_USART1=y
|
||||
CONFIG_STM32_USART2=y
|
||||
CONFIG_STM32_USART3=y
|
||||
CONFIG_STM32_USART6=y
|
||||
CONFIG_STM32_USART_BREAKS=y
|
||||
CONFIG_STM32_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32_WWDG=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=300
|
||||
CONFIG_UART4_RXDMA=y
|
||||
CONFIG_UART4_TXBUFSIZE=300
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=300
|
||||
CONFIG_UART7_RXDMA=y
|
||||
CONFIG_UART7_SERIAL_CONSOLE=y
|
||||
CONFIG_UART7_TXBUFSIZE=300
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=300
|
||||
CONFIG_UART8_TXBUFSIZE=300
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_RXDMA=y
|
||||
CONFIG_USART1_TXBUFSIZE=2500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_RXDMA=y
|
||||
CONFIG_USART2_TXBUFSIZE=1100
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=1200
|
||||
CONFIG_USART3_RXDMA=y
|
||||
CONFIG_USART3_TXBUFSIZE=900
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=300
|
||||
CONFIG_USART6_RXDMA=y
|
||||
CONFIG_USART6_TXBUFSIZE=300
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
@@ -0,0 +1,119 @@
|
||||
|
||||
# set Release for -O3
|
||||
set(CMAKE_BUILD_TYPE "Release" CACHE STRING "Build type" FORCE)
|
||||
add_compile_options(-Wno-error=array-bounds)
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v4
|
||||
LABEL optimized
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
ROMFSROOT px4fmu_common
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 1
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
#imu/analog_devices/adis16448
|
||||
#imu/adis16477
|
||||
#imu/adis16497
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
#imu/invensense/icm40609d
|
||||
#imu/invensense/mpu6500
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
#roboclaw
|
||||
safety_button
|
||||
#tap_esc
|
||||
#telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
#uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
#attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
#landing_target_estimator
|
||||
load_mon
|
||||
#local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
#rover_pos_control
|
||||
sensors
|
||||
#sih
|
||||
temperature_compensation
|
||||
#uuv_att_control
|
||||
#vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
)
|
||||
@@ -0,0 +1,130 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v4
|
||||
LABEL rtps
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
ROMFSROOT px4fmu_common
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 1
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/icm40609d
|
||||
imu/invensense/mpu6500
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -0,0 +1,129 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v4
|
||||
LABEL stackcheck
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
ROMFSROOT px4fmu_common
|
||||
TESTING
|
||||
#UAVCAN_INTERFACES 1
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
#imu/analog_devices/adis16448
|
||||
#imu/adis16477
|
||||
#imu/adis16497
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
#imu/invensense/icm40609d
|
||||
#imu/invensense/mpu6500
|
||||
#imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
#roboclaw
|
||||
safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
#uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
#uuv_att_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
#fake_gps
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#uuv_example_app
|
||||
#work_item
|
||||
)
|
||||
@@ -0,0 +1,129 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v4pro
|
||||
LABEL rtps
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
ROMFSROOT px4fmu_common
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
TEL3:/dev/ttyS0
|
||||
TEL4:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
pca9685
|
||||
power_monitor/ina226
|
||||
protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -0,0 +1,131 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v5
|
||||
LABEL critmonitor
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS3
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/bosch/bmi055
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20689
|
||||
#imu/mpu6000 # legacy icm20602/icm20689 driver
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
rc_input
|
||||
roboclaw
|
||||
safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -0,0 +1,132 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v5
|
||||
LABEL irqmonitor
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS3
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/bosch/bmi055
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20689
|
||||
#imu/mpu6000 # legacy icm20602/icm20689 driver
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -0,0 +1,245 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_FS_PROCFS_EXCLUDE_ENVIRON is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32f7"
|
||||
CONFIG_ARCH_CHIP_STM32F765II=y
|
||||
CONFIG_ARCH_CHIP_STM32F7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0032
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v5.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_VENDORSTR="3D Robotics"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_DISABLE_MQUEUE=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
CONFIG_MM_REGIONS=3
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_IFCONFIG=y
|
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_CRITMONITOR=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDMMC1_SDIO_MODE=y
|
||||
CONFIG_SDMMC1_SDIO_PULLUP=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=256
|
||||
CONFIG_STM32F7_ADC1=y
|
||||
CONFIG_STM32F7_BBSRAM=y
|
||||
CONFIG_STM32F7_BBSRAM_FILES=5
|
||||
CONFIG_STM32F7_BKPSRAM=y
|
||||
CONFIG_STM32F7_DMA1=y
|
||||
CONFIG_STM32F7_DMA2=y
|
||||
CONFIG_STM32F7_DMACAPABLE=y
|
||||
CONFIG_STM32F7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32F7_I2C1=y
|
||||
CONFIG_STM32F7_I2C2=y
|
||||
CONFIG_STM32F7_I2C3=y
|
||||
CONFIG_STM32F7_I2C4=y
|
||||
CONFIG_STM32F7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32F7_OTGFS=y
|
||||
CONFIG_STM32F7_PROGMEM=y
|
||||
CONFIG_STM32F7_PWR=y
|
||||
CONFIG_STM32F7_RTC=y
|
||||
CONFIG_STM32F7_RTC_HSECLOCK=y
|
||||
CONFIG_STM32F7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32F7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32F7_SDMMC1=y
|
||||
CONFIG_STM32F7_SDMMC_DMA=y
|
||||
CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32F7_SPI1=y
|
||||
CONFIG_STM32F7_SPI1_DMA=y
|
||||
CONFIG_STM32F7_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32F7_SPI2=y
|
||||
CONFIG_STM32F7_SPI4=y
|
||||
CONFIG_STM32F7_SPI5=y
|
||||
CONFIG_STM32F7_SPI6=y
|
||||
CONFIG_STM32F7_SPI_DMA=y
|
||||
CONFIG_STM32F7_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32F7_TIM10=y
|
||||
CONFIG_STM32F7_TIM11=y
|
||||
CONFIG_STM32F7_UART4=y
|
||||
CONFIG_STM32F7_UART7=y
|
||||
CONFIG_STM32F7_UART8=y
|
||||
CONFIG_STM32F7_USART1=y
|
||||
CONFIG_STM32F7_USART2=y
|
||||
CONFIG_STM32F7_USART3=y
|
||||
CONFIG_STM32F7_USART6=y
|
||||
CONFIG_STM32F7_USART_BREAKS=y
|
||||
CONFIG_STM32F7_USART_INVERT=y
|
||||
CONFIG_STM32F7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32F7_USART_SWAP=y
|
||||
CONFIG_STM32F7_WWDG=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_CRITMONITOR=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_RXDMA=y
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_SERIAL_CONSOLE=y
|
||||
CONFIG_UART7_TXBUFSIZE=1500
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=600
|
||||
CONFIG_UART8_RXDMA=y
|
||||
CONFIG_UART8_TXBUFSIZE=1500
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_TXBUFSIZE=1500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_RXDMA=y
|
||||
CONFIG_USART2_TXBUFSIZE=1500
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_RXDMA=y
|
||||
CONFIG_USART3_TXBUFSIZE=3000
|
||||
CONFIG_USART3_TXDMA=y
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_RXDMA=y
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
@@ -0,0 +1,244 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_FS_PROCFS_EXCLUDE_ENVIRON is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32f7"
|
||||
CONFIG_ARCH_CHIP_STM32F765II=y
|
||||
CONFIG_ARCH_CHIP_STM32F7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0032
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v5.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_VENDORSTR="3D Robotics"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_DISABLE_MQUEUE=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
CONFIG_MM_REGIONS=3
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_IFCONFIG=y
|
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_IRQMONITOR=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDMMC1_SDIO_MODE=y
|
||||
CONFIG_SDMMC1_SDIO_PULLUP=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=256
|
||||
CONFIG_STM32F7_ADC1=y
|
||||
CONFIG_STM32F7_BBSRAM=y
|
||||
CONFIG_STM32F7_BBSRAM_FILES=5
|
||||
CONFIG_STM32F7_BKPSRAM=y
|
||||
CONFIG_STM32F7_DMA1=y
|
||||
CONFIG_STM32F7_DMA2=y
|
||||
CONFIG_STM32F7_DMACAPABLE=y
|
||||
CONFIG_STM32F7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32F7_I2C1=y
|
||||
CONFIG_STM32F7_I2C2=y
|
||||
CONFIG_STM32F7_I2C3=y
|
||||
CONFIG_STM32F7_I2C4=y
|
||||
CONFIG_STM32F7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32F7_OTGFS=y
|
||||
CONFIG_STM32F7_PROGMEM=y
|
||||
CONFIG_STM32F7_PWR=y
|
||||
CONFIG_STM32F7_RTC=y
|
||||
CONFIG_STM32F7_RTC_HSECLOCK=y
|
||||
CONFIG_STM32F7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32F7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32F7_SDMMC1=y
|
||||
CONFIG_STM32F7_SDMMC_DMA=y
|
||||
CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32F7_SPI1=y
|
||||
CONFIG_STM32F7_SPI1_DMA=y
|
||||
CONFIG_STM32F7_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32F7_SPI2=y
|
||||
CONFIG_STM32F7_SPI4=y
|
||||
CONFIG_STM32F7_SPI5=y
|
||||
CONFIG_STM32F7_SPI6=y
|
||||
CONFIG_STM32F7_SPI_DMA=y
|
||||
CONFIG_STM32F7_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32F7_TIM10=y
|
||||
CONFIG_STM32F7_TIM11=y
|
||||
CONFIG_STM32F7_UART4=y
|
||||
CONFIG_STM32F7_UART7=y
|
||||
CONFIG_STM32F7_UART8=y
|
||||
CONFIG_STM32F7_USART1=y
|
||||
CONFIG_STM32F7_USART2=y
|
||||
CONFIG_STM32F7_USART3=y
|
||||
CONFIG_STM32F7_USART6=y
|
||||
CONFIG_STM32F7_USART_BREAKS=y
|
||||
CONFIG_STM32F7_USART_INVERT=y
|
||||
CONFIG_STM32F7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32F7_USART_SWAP=y
|
||||
CONFIG_STM32F7_WWDG=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_RXDMA=y
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_SERIAL_CONSOLE=y
|
||||
CONFIG_UART7_TXBUFSIZE=1500
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=600
|
||||
CONFIG_UART8_RXDMA=y
|
||||
CONFIG_UART8_TXBUFSIZE=1500
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_TXBUFSIZE=1500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_RXDMA=y
|
||||
CONFIG_USART2_TXBUFSIZE=1500
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_RXDMA=y
|
||||
CONFIG_USART3_TXBUFSIZE=3000
|
||||
CONFIG_USART3_TXDMA=y
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_RXDMA=y
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
@@ -0,0 +1,280 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_ARP is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743ZI=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_STACKCHECK=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95751
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0036
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v6U.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x1B8C
|
||||
CONFIG_CDCACM_VENDORSTR="Gumstix"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_MEMFAULT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_ETH0_PHY_LAN8742A=y
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_IOB_NBUFFERS=24
|
||||
CONFIG_IOB_THROTTLE=0
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
CONFIG_MM_REGIONS=3
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_PROGMEM=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NET=y
|
||||
CONFIG_NETDB_DNSCLIENT=y
|
||||
CONFIG_NETDB_DNSCLIENT_ENTRIES=8
|
||||
CONFIG_NETDB_DNSSERVER_NOADDR=y
|
||||
CONFIG_NETDEV_PHY_IOCTL=y
|
||||
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
|
||||
CONFIG_NETINIT_IPADDR=0XC0A8007B
|
||||
CONFIG_NETINIT_THREAD=y
|
||||
CONFIG_NETINIT_THREAD_PRIORITY=49
|
||||
CONFIG_NETUTILS_TELNETD=y
|
||||
CONFIG_NET_ARP_IPIN=y
|
||||
CONFIG_NET_ARP_SEND=y
|
||||
CONFIG_NET_BROADCAST=y
|
||||
CONFIG_NET_ICMP=y
|
||||
CONFIG_NET_ICMP_SOCKET=y
|
||||
CONFIG_NET_SOCKOPTS=y
|
||||
CONFIG_NET_SOLINGER=y
|
||||
CONFIG_NET_TCP=y
|
||||
CONFIG_NET_TCPBACKLOG=y
|
||||
CONFIG_NET_TCP_WRITE_BUFFERS=y
|
||||
CONFIG_NET_UDP=y
|
||||
CONFIG_NET_UDP_CHECKSUMS=y
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_TELNET=y
|
||||
CONFIG_NSH_TELNET_LOGIN=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDMMC2_SDIO_PULLUP=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=256
|
||||
CONFIG_STM32H7_ADC1=y
|
||||
CONFIG_STM32H7_ADC3=y
|
||||
CONFIG_STM32H7_BBSRAM=y
|
||||
CONFIG_STM32H7_BBSRAM_FILES=5
|
||||
CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_DTCMEXCLUDE=y
|
||||
CONFIG_STM32H7_DTCM_PROCFS=y
|
||||
CONFIG_STM32H7_ETHMAC=y
|
||||
CONFIG_STM32H7_FLASH_OVERRIDE_I=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C2=y
|
||||
CONFIG_STM32H7_I2C3=y
|
||||
CONFIG_STM32H7_I2C4=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PHYSR=31
|
||||
CONFIG_STM32H7_PHYSR_100MBPS=0x8
|
||||
CONFIG_STM32H7_PHYSR_FULLDUPLEX=0x10
|
||||
CONFIG_STM32H7_PHYSR_MODE=0x10
|
||||
CONFIG_STM32H7_PHYSR_SPEED=0x8
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC2=y
|
||||
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_SPI1=y
|
||||
CONFIG_STM32H7_SPI1_DMA=y
|
||||
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI2_DMA=y
|
||||
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
|
||||
CONFIG_STM32H7_SPI3=y
|
||||
CONFIG_STM32H7_SPI3_DMA=y
|
||||
CONFIG_STM32H7_SPI3_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI5=y
|
||||
CONFIG_STM32H7_SPI6=y
|
||||
CONFIG_STM32H7_SPI6_DMA=y
|
||||
CONFIG_STM32H7_SPI6_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI_DMA=y
|
||||
CONFIG_STM32H7_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32H7_TIM12=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM4=y
|
||||
CONFIG_STM32H7_TIM5=y
|
||||
CONFIG_STM32H7_UART4=y
|
||||
CONFIG_STM32H7_UART5=y
|
||||
CONFIG_STM32H7_UART7=y
|
||||
CONFIG_STM32H7_UART8=y
|
||||
CONFIG_STM32H7_USART1=y
|
||||
CONFIG_STM32H7_USART2=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_USART6=y
|
||||
CONFIG_STM32H7_USART_BREAKS=y
|
||||
CONFIG_STM32H7_USART_INVERT=y
|
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32H7_USART_SWAP=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART5_IFLOWCONTROL=y
|
||||
CONFIG_UART5_OFLOWCONTROL=y
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_IFLOWCONTROL=y
|
||||
CONFIG_UART7_OFLOWCONTROL=y
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_TXBUFSIZE=3000
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=600
|
||||
CONFIG_UART8_TXBUFSIZE=1500
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_TXBUFSIZE=1500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_TXBUFSIZE=3000
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_RXBUFSIZE=180
|
||||
CONFIG_USART3_SERIAL_CONSOLE=y
|
||||
CONFIG_USART3_TXBUFSIZE=1500
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
@@ -0,0 +1,135 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v6u
|
||||
LABEL default
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
BUILD_BOOTLOADER
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 1
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS6
|
||||
TEL2:/dev/ttyS4
|
||||
TEL3:/dev/ttyS1
|
||||
GPS2:/dev/ttyS7
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm42605
|
||||
imu/invensense/icm42688p
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
# pwm_input - Need to create arch/stm32 arch/stm32h7 arch/kinetis and reloacate
|
||||
# all arch dependant code there
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
serial_test
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -0,0 +1,280 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_ARP is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743ZI=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_STACKCHECK=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95751
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0035
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v6X.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x3185
|
||||
CONFIG_CDCACM_VENDORSTR="Auterion"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_MEMFAULT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_ETH0_PHY_LAN8742A=y
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_IOB_NBUFFERS=24
|
||||
CONFIG_IOB_THROTTLE=0
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MAX_TASKS=64
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
CONFIG_MM_REGIONS=3
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_PROGMEM=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NET=y
|
||||
CONFIG_NETDB_DNSCLIENT=y
|
||||
CONFIG_NETDB_DNSCLIENT_ENTRIES=8
|
||||
CONFIG_NETDB_DNSSERVER_NOADDR=y
|
||||
CONFIG_NETDEV_PHY_IOCTL=y
|
||||
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
|
||||
CONFIG_NETINIT_IPADDR=0XC0A8007B
|
||||
CONFIG_NETINIT_THREAD=y
|
||||
CONFIG_NETINIT_THREAD_PRIORITY=49
|
||||
CONFIG_NETUTILS_TELNETD=y
|
||||
CONFIG_NET_ARP_IPIN=y
|
||||
CONFIG_NET_ARP_SEND=y
|
||||
CONFIG_NET_BROADCAST=y
|
||||
CONFIG_NET_ICMP=y
|
||||
CONFIG_NET_ICMP_SOCKET=y
|
||||
CONFIG_NET_SOCKOPTS=y
|
||||
CONFIG_NET_SOLINGER=y
|
||||
CONFIG_NET_TCP=y
|
||||
CONFIG_NET_TCPBACKLOG=y
|
||||
CONFIG_NET_TCP_WRITE_BUFFERS=y
|
||||
CONFIG_NET_UDP=y
|
||||
CONFIG_NET_UDP_CHECKSUMS=y
|
||||
CONFIG_NFILE_DESCRIPTORS=12
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_TELNET=y
|
||||
CONFIG_NSH_TELNET_LOGIN=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDMMC2_SDIO_PULLUP=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=256
|
||||
CONFIG_STM32H7_ADC1=y
|
||||
CONFIG_STM32H7_ADC3=y
|
||||
CONFIG_STM32H7_BBSRAM=y
|
||||
CONFIG_STM32H7_BBSRAM_FILES=5
|
||||
CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_DTCMEXCLUDE=y
|
||||
CONFIG_STM32H7_DTCM_PROCFS=y
|
||||
CONFIG_STM32H7_ETHMAC=y
|
||||
CONFIG_STM32H7_FLASH_OVERRIDE_I=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C2=y
|
||||
CONFIG_STM32H7_I2C3=y
|
||||
CONFIG_STM32H7_I2C4=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PHYSR=31
|
||||
CONFIG_STM32H7_PHYSR_100MBPS=0x8
|
||||
CONFIG_STM32H7_PHYSR_FULLDUPLEX=0x10
|
||||
CONFIG_STM32H7_PHYSR_MODE=0x10
|
||||
CONFIG_STM32H7_PHYSR_SPEED=0x8
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC2=y
|
||||
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_SPI1=y
|
||||
CONFIG_STM32H7_SPI1_DMA=y
|
||||
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI2_DMA=y
|
||||
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
|
||||
CONFIG_STM32H7_SPI3=y
|
||||
CONFIG_STM32H7_SPI3_DMA=y
|
||||
CONFIG_STM32H7_SPI3_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI5=y
|
||||
CONFIG_STM32H7_SPI6=y
|
||||
CONFIG_STM32H7_SPI6_DMA=y
|
||||
CONFIG_STM32H7_SPI6_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI_DMA=y
|
||||
CONFIG_STM32H7_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32H7_TIM12=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM4=y
|
||||
CONFIG_STM32H7_TIM5=y
|
||||
CONFIG_STM32H7_UART4=y
|
||||
CONFIG_STM32H7_UART5=y
|
||||
CONFIG_STM32H7_UART7=y
|
||||
CONFIG_STM32H7_UART8=y
|
||||
CONFIG_STM32H7_USART1=y
|
||||
CONFIG_STM32H7_USART2=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_USART6=y
|
||||
CONFIG_STM32H7_USART_BREAKS=y
|
||||
CONFIG_STM32H7_USART_INVERT=y
|
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32H7_USART_SWAP=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART5_IFLOWCONTROL=y
|
||||
CONFIG_UART5_OFLOWCONTROL=y
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_IFLOWCONTROL=y
|
||||
CONFIG_UART7_OFLOWCONTROL=y
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_TXBUFSIZE=3000
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=600
|
||||
CONFIG_UART8_TXBUFSIZE=1500
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_TXBUFSIZE=1500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_TXBUFSIZE=3000
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_RXBUFSIZE=180
|
||||
CONFIG_USART3_SERIAL_CONSOLE=y
|
||||
CONFIG_USART3_TXBUFSIZE=1500
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
@@ -0,0 +1,132 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
MODEL fmu-v6x
|
||||
LABEL default
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
BUILD_BOOTLOADER
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
# UAVCAN_INTERFACES 2 - No H7 or FD can support in UAVCAN
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS6
|
||||
TEL2:/dev/ttyS4
|
||||
TEL3:/dev/ttyS1
|
||||
GPS2:/dev/ttyS7
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20649
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
# pwm_input - Need to create arch/stm32 arch/stm32h7 arch/kinetis and reloacate
|
||||
# all arch dependant code there
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
# uavcan - No H7 or FD can support in UAVCAN yet
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
serial_test
|
||||
EXAMPLES
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -23,6 +23,7 @@ uint64 timestamp_last_signal # last valid reception time
|
||||
|
||||
uint8 channel_count # number of channels actually being seen
|
||||
|
||||
int8 RSSI_MAX = 100
|
||||
int32 rssi # receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception
|
||||
|
||||
bool rc_failsafe # explicit failsafe flag: true on TX failure or TX out of range , false otherwise. Only the true state is reliable, as there are some (PPM) receivers on the market going into failsafe without telling us explicitly.
|
||||
|
||||
@@ -26,12 +26,4 @@ uint8 kill_switch # throttle kill: _NORMAL_, KILL
|
||||
uint8 gear_switch # landing gear switch: _DOWN_, UP
|
||||
uint8 transition_switch # VTOL transition switch: _HOVER, FORWARD_FLIGHT
|
||||
|
||||
# legacy "advanced" switch configuration (will be removed soon)
|
||||
uint8 mode_switch # main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO
|
||||
uint8 man_switch # manual switch (only relevant for fixed wings, optional): _STABILIZED_, MANUAL
|
||||
uint8 acro_switch # acro 2 position switch (optional): _MANUAL_, ACRO
|
||||
uint8 rattitude_switch # rattitude control 2 position switch (optional): _MANUAL, RATTITUDE
|
||||
uint8 stab_switch # stabilize switch (only relevant for fixed wings, optional): _MANUAL, STABILIZED
|
||||
uint8 posctl_switch # position control 2 position switch (optional): _ALTCTL_, POSCTL
|
||||
|
||||
uint32 switch_changes # number of switch changes
|
||||
|
||||
+17
-28
@@ -6,49 +6,38 @@ float32 voltage_v # Servo rail voltage in volts
|
||||
float32 rssi_v # RSSI pin voltage in volts
|
||||
|
||||
# PX4IO status flags (PX4IO_P_STATUS_FLAGS)
|
||||
bool status_outputs_armed
|
||||
bool status_override
|
||||
bool status_rc_ok
|
||||
bool status_rc_ppm
|
||||
bool status_rc_dsm
|
||||
bool status_rc_sbus
|
||||
bool status_fmu_ok
|
||||
bool status_raw_pwm
|
||||
bool status_mixer_ok
|
||||
bool status_arm_sync
|
||||
bool status_init_ok
|
||||
bool status_failsafe
|
||||
bool status_safety_off
|
||||
bool status_fmu_initialized
|
||||
bool status_fmu_ok
|
||||
bool status_init_ok
|
||||
bool status_outputs_armed
|
||||
bool status_raw_pwm
|
||||
bool status_rc_ok
|
||||
bool status_rc_dsm
|
||||
bool status_rc_ppm
|
||||
bool status_rc_sbus
|
||||
bool status_rc_st24
|
||||
bool status_rc_sumd
|
||||
bool status_safety_off
|
||||
|
||||
# PX4IO alarms (PX4IO_P_STATUS_ALARMS)
|
||||
bool alarm_vbatt_low
|
||||
bool alarm_temperature
|
||||
bool alarm_servo_current
|
||||
bool alarm_acc_current
|
||||
bool alarm_fmu_lost
|
||||
bool alarm_rc_lost
|
||||
bool alarm_pwm_error
|
||||
bool alarm_vservo_fault
|
||||
bool alarm_rc_lost
|
||||
|
||||
# PX4IO arming (PX4IO_P_SETUP_ARMING)
|
||||
bool arming_io_arm_ok
|
||||
bool arming_failsafe_custom
|
||||
bool arming_fmu_armed
|
||||
bool arming_fmu_prearmed
|
||||
bool arming_manual_override_ok
|
||||
bool arming_failsafe_custom
|
||||
bool arming_inair_restart_ok
|
||||
bool arming_always_pwm_enable
|
||||
bool arming_rc_handling_disabled
|
||||
bool arming_lockdown
|
||||
bool arming_force_failsafe
|
||||
bool arming_io_arm_ok
|
||||
bool arming_lockdown
|
||||
bool arming_termination_failsafe
|
||||
bool arming_override_immediate
|
||||
|
||||
uint16[8] pwm
|
||||
uint16[8] pwm_disarmed
|
||||
uint16[8] pwm_failsafe
|
||||
|
||||
int16[8] actuators
|
||||
uint16[8] servos
|
||||
uint16[8] pwm_rate_hz
|
||||
|
||||
uint16[18] raw_inputs
|
||||
|
||||
+22
-28
@@ -1,37 +1,31 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
uint8 FUNCTION_THROTTLE=0
|
||||
uint8 FUNCTION_ROLL=1
|
||||
uint8 FUNCTION_PITCH=2
|
||||
uint8 FUNCTION_YAW=3
|
||||
uint8 FUNCTION_MODE=4
|
||||
uint8 FUNCTION_RETURN=5
|
||||
uint8 FUNCTION_POSCTL=6
|
||||
uint8 FUNCTION_LOITER=7
|
||||
uint8 FUNCTION_OFFBOARD=8
|
||||
uint8 FUNCTION_ACRO=9
|
||||
uint8 FUNCTION_FLAPS=10
|
||||
uint8 FUNCTION_AUX_1=11
|
||||
uint8 FUNCTION_AUX_2=12
|
||||
uint8 FUNCTION_AUX_3=13
|
||||
uint8 FUNCTION_AUX_4=14
|
||||
uint8 FUNCTION_AUX_5=15
|
||||
uint8 FUNCTION_PARAM_1=16
|
||||
uint8 FUNCTION_PARAM_2=17
|
||||
uint8 FUNCTION_PARAM_3_5=18
|
||||
uint8 FUNCTION_RATTITUDE=19
|
||||
uint8 FUNCTION_KILLSWITCH=20
|
||||
uint8 FUNCTION_TRANSITION=21
|
||||
uint8 FUNCTION_GEAR=22
|
||||
uint8 FUNCTION_ARMSWITCH=23
|
||||
uint8 FUNCTION_STAB=24
|
||||
uint8 FUNCTION_AUX_6=25
|
||||
uint8 FUNCTION_MAN=26
|
||||
uint8 FUNCTION_THROTTLE = 0
|
||||
uint8 FUNCTION_ROLL = 1
|
||||
uint8 FUNCTION_PITCH = 2
|
||||
uint8 FUNCTION_YAW = 3
|
||||
uint8 FUNCTION_RETURN = 4
|
||||
uint8 FUNCTION_LOITER = 5
|
||||
uint8 FUNCTION_OFFBOARD = 6
|
||||
uint8 FUNCTION_FLAPS = 7
|
||||
uint8 FUNCTION_AUX_1 = 8
|
||||
uint8 FUNCTION_AUX_2 = 9
|
||||
uint8 FUNCTION_AUX_3 = 10
|
||||
uint8 FUNCTION_AUX_4 = 11
|
||||
uint8 FUNCTION_AUX_5 = 12
|
||||
uint8 FUNCTION_AUX_6 = 13
|
||||
uint8 FUNCTION_PARAM_1 = 14
|
||||
uint8 FUNCTION_PARAM_2 = 15
|
||||
uint8 FUNCTION_PARAM_3_5 = 16
|
||||
uint8 FUNCTION_KILLSWITCH = 17
|
||||
uint8 FUNCTION_TRANSITION = 18
|
||||
uint8 FUNCTION_GEAR = 19
|
||||
uint8 FUNCTION_ARMSWITCH = 20
|
||||
|
||||
uint64 timestamp_last_valid # Timestamp of last valid RC signal
|
||||
float32[18] channels # Scaled to -1..1 (throttle: 0..1)
|
||||
uint8 channel_count # Number of valid channels
|
||||
int8[27] function # Functions mapping
|
||||
int8[21] function # Functions mapping
|
||||
uint8 rssi # Receive signal strength index
|
||||
bool signal_lost # Control signal lost, should be checked together with topic timeout
|
||||
uint32 frame_drop_count # Number of dropped frames
|
||||
|
||||
@@ -1,5 +1,3 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
bool safety_switch_available # Set to true if a safety switch is connected
|
||||
bool safety_off # Set to true if safety is off
|
||||
bool override_available # Set to true if external override system is connected
|
||||
bool override_enabled # Set to true if override is engaged
|
||||
|
||||
@@ -1,8 +1,6 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
bool flag_armed # synonym for actuator_armed.armed
|
||||
|
||||
bool flag_external_manual_override_ok # external override non-fatal for system. Only true for fixed wing
|
||||
|
||||
bool flag_control_manual_enabled # true if manual input is mixed in
|
||||
bool flag_control_auto_enabled # true if onboard autopilot should act
|
||||
bool flag_control_offboard_enabled # true if offboard control should be used
|
||||
|
||||
@@ -228,7 +228,7 @@
|
||||
# else
|
||||
/* Use PX4IO FW search paths defaults based on version */
|
||||
# if BOARD_USES_PX4IO_VERSION == 2
|
||||
# define PX4IO_FW_SEARCH_PATHS {"/etc/extras/px4_io-v2_default.bin","/fs/microsd/px4_io-v2_default.bin", "/fs/microsd/px4io2.bin", nullptr }
|
||||
# define PX4IO_FW_SEARCH_PATHS {"/etc/extras/px4_io-v2_default.bin","/fs/microsd/px4_io-v2_default.bin", nullptr }
|
||||
# endif
|
||||
# endif
|
||||
#endif
|
||||
|
||||
@@ -66,7 +66,7 @@ static constexpr wq_config_t I2C3{"wq:I2C3", 2336, -11};
|
||||
static constexpr wq_config_t I2C4{"wq:I2C4", 2336, -12};
|
||||
|
||||
// PX4 att/pos controllers, highest priority after sensors.
|
||||
static constexpr wq_config_t nav_and_controllers{"wq:nav_and_controllers", 1824, -13};
|
||||
static constexpr wq_config_t nav_and_controllers{"wq:nav_and_controllers", 1792, -13};
|
||||
|
||||
static constexpr wq_config_t INS0{"wq:INS0", 6000, -14};
|
||||
static constexpr wq_config_t INS1{"wq:INS1", 6000, -15};
|
||||
@@ -77,16 +77,16 @@ static constexpr wq_config_t hp_default{"wq:hp_default", 1900, -18};
|
||||
|
||||
static constexpr wq_config_t uavcan{"wq:uavcan", 2576, -19};
|
||||
|
||||
static constexpr wq_config_t UART0{"wq:UART0", 1400, -21};
|
||||
static constexpr wq_config_t UART1{"wq:UART1", 1400, -22};
|
||||
static constexpr wq_config_t UART2{"wq:UART2", 1400, -23};
|
||||
static constexpr wq_config_t UART3{"wq:UART3", 1400, -24};
|
||||
static constexpr wq_config_t UART4{"wq:UART4", 1400, -25};
|
||||
static constexpr wq_config_t UART5{"wq:UART5", 1400, -26};
|
||||
static constexpr wq_config_t UART6{"wq:UART6", 1400, -27};
|
||||
static constexpr wq_config_t UART7{"wq:UART7", 1400, -28};
|
||||
static constexpr wq_config_t UART8{"wq:UART8", 1400, -29};
|
||||
static constexpr wq_config_t UART_UNKNOWN{"wq:UART_UNKNOWN", 1400, -30};
|
||||
static constexpr wq_config_t UART0{"wq:UART0", 1632, -21};
|
||||
static constexpr wq_config_t UART1{"wq:UART1", 1632, -22};
|
||||
static constexpr wq_config_t UART2{"wq:UART2", 1632, -23};
|
||||
static constexpr wq_config_t UART3{"wq:UART3", 1632, -24};
|
||||
static constexpr wq_config_t UART4{"wq:UART4", 1632, -25};
|
||||
static constexpr wq_config_t UART5{"wq:UART5", 1632, -26};
|
||||
static constexpr wq_config_t UART6{"wq:UART6", 1632, -27};
|
||||
static constexpr wq_config_t UART7{"wq:UART7", 1632, -28};
|
||||
static constexpr wq_config_t UART8{"wq:UART8", 1632, -29};
|
||||
static constexpr wq_config_t UART_UNKNOWN{"wq:UART_UNKNOWN", 1632, -30};
|
||||
|
||||
static constexpr wq_config_t lp_default{"wq:lp_default", 1700, -50};
|
||||
|
||||
|
||||
@@ -10,7 +10,6 @@ set(tests
|
||||
bson
|
||||
commander
|
||||
controllib
|
||||
conv
|
||||
dataman
|
||||
file2
|
||||
float
|
||||
|
||||
@@ -77,8 +77,6 @@ const char *get_commands()
|
||||
"param set RC6_MIN 992\n"
|
||||
"param set RC6_TRIM 1504\n"
|
||||
"param set RC_CHAN_CNT 8\n"
|
||||
"param set RC_MAP_MODE_SW 5\n"
|
||||
"param set RC_MAP_POSCTL_SW 7\n"
|
||||
"param set RC_MAP_RETURN_SW 8\n"
|
||||
"param set MC_YAW_P 1.5\n"
|
||||
"param set MC_PITCH_P 3.0\n"
|
||||
|
||||
@@ -34,7 +34,6 @@ px4_add_module(
|
||||
MODULE drivers__camera_trigger
|
||||
MAIN camera_trigger
|
||||
COMPILE_FLAGS
|
||||
-O0
|
||||
SRCS
|
||||
camera_trigger.cpp
|
||||
interfaces/src/camera_interface.cpp
|
||||
|
||||
@@ -69,6 +69,8 @@
|
||||
#include "interfaces/src/pwm.h"
|
||||
#include "interfaces/src/seagull_map2.h"
|
||||
|
||||
extern "C" __EXPORT int camera_trigger_main(int argc, char *argv[]);
|
||||
|
||||
typedef enum : int32_t {
|
||||
CAMERA_INTERFACE_MODE_NONE = 0,
|
||||
CAMERA_INTERFACE_MODE_GPIO,
|
||||
@@ -152,41 +154,41 @@ public:
|
||||
|
||||
private:
|
||||
|
||||
struct hrt_call _engagecall {};
|
||||
struct hrt_call _disengagecall {};
|
||||
struct hrt_call _engage_turn_on_off_call {};
|
||||
struct hrt_call _disengage_turn_on_off_call {};
|
||||
struct hrt_call _keepalivecall_up {};
|
||||
struct hrt_call _keepalivecall_down {};
|
||||
struct hrt_call _engagecall;
|
||||
struct hrt_call _disengagecall;
|
||||
struct hrt_call _engage_turn_on_off_call;
|
||||
struct hrt_call _disengage_turn_on_off_call;
|
||||
struct hrt_call _keepalivecall_up;
|
||||
struct hrt_call _keepalivecall_down;
|
||||
|
||||
float _activation_time{0.5f};
|
||||
float _interval{100.f};
|
||||
float _min_interval{1.f};
|
||||
float _distance{25.f};
|
||||
uint32_t _trigger_seq{0};
|
||||
hrt_abstime _last_trigger_timestamp{0};
|
||||
bool _trigger_enabled{false};
|
||||
bool _trigger_paused{false};
|
||||
bool _one_shot{false};
|
||||
bool _test_shot{false};
|
||||
bool _turning_on{false};
|
||||
matrix::Vector2f _last_shoot_position{0.f, 0.f};
|
||||
bool _valid_position{false};
|
||||
float _activation_time;
|
||||
float _interval;
|
||||
float _min_interval;
|
||||
float _distance;
|
||||
uint32_t _trigger_seq;
|
||||
hrt_abstime _last_trigger_timestamp;
|
||||
bool _trigger_enabled;
|
||||
bool _trigger_paused;
|
||||
bool _one_shot;
|
||||
bool _test_shot;
|
||||
bool _turning_on;
|
||||
matrix::Vector2f _last_shoot_position;
|
||||
bool _valid_position;
|
||||
|
||||
//Camera Auto Mount Pivoting Oblique Survey (CAMPOS)
|
||||
uint32_t _CAMPOS_num_poses{0};
|
||||
uint32_t _CAMPOS_pose_counter{0};
|
||||
float _CAMPOS_roll_angle{0.f};
|
||||
float _CAMPOS_angle_interval{0.f};
|
||||
float _CAMPOS_pitch_angle{-90.f};
|
||||
bool _CAMPOS_updated_roll_angle{false};
|
||||
uint32_t _target_system{0};
|
||||
uint32_t _target_component{0};
|
||||
uint32_t _CAMPOS_num_poses;
|
||||
uint32_t _CAMPOS_pose_counter;
|
||||
float _CAMPOS_roll_angle;
|
||||
float _CAMPOS_angle_interval;
|
||||
float _CAMPOS_pitch_angle;
|
||||
bool _CAMPOS_updated_roll_angle;
|
||||
uint32_t _target_system;
|
||||
uint32_t _target_component;
|
||||
|
||||
uORB::Subscription _command_sub{ORB_ID(vehicle_command)};
|
||||
uORB::Subscription _lpos_sub{ORB_ID(vehicle_local_position)};
|
||||
|
||||
orb_advert_t _trigger_pub{nullptr};
|
||||
orb_advert_t _trigger_pub;
|
||||
|
||||
uORB::Publication<vehicle_command_ack_s> _cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
|
||||
@@ -198,11 +200,11 @@ private:
|
||||
param_t _p_interface;
|
||||
param_t _p_cam_cap_fback;
|
||||
|
||||
trigger_mode_t _trigger_mode{TRIGGER_MODE_NONE};
|
||||
int32_t _cam_cap_fback{0};
|
||||
trigger_mode_t _trigger_mode;
|
||||
int32_t _cam_cap_fback;
|
||||
|
||||
camera_interface_mode_t _camera_interface_mode{CAMERA_INTERFACE_MODE_GPIO};
|
||||
CameraInterface *_camera_interface{nullptr}; ///< instance of camera interface
|
||||
camera_interface_mode_t _camera_interface_mode;
|
||||
CameraInterface *_camera_interface; ///< instance of camera interface
|
||||
|
||||
/**
|
||||
* Vehicle command handler
|
||||
@@ -246,7 +248,39 @@ CameraTrigger *g_camera_trigger;
|
||||
}
|
||||
|
||||
CameraTrigger::CameraTrigger() :
|
||||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default)
|
||||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default),
|
||||
_engagecall {},
|
||||
_disengagecall {},
|
||||
_engage_turn_on_off_call {},
|
||||
_disengage_turn_on_off_call {},
|
||||
_keepalivecall_up {},
|
||||
_keepalivecall_down {},
|
||||
_activation_time(0.5f /* ms */),
|
||||
_interval(100.0f /* ms */),
|
||||
_min_interval(1.0f /* ms */),
|
||||
_distance(25.0f /* m */),
|
||||
_trigger_seq(0),
|
||||
_last_trigger_timestamp(0),
|
||||
_trigger_enabled(false),
|
||||
_trigger_paused(false),
|
||||
_one_shot(false),
|
||||
_test_shot(false),
|
||||
_turning_on(false),
|
||||
_last_shoot_position(0.0f, 0.0f),
|
||||
_valid_position(false),
|
||||
_CAMPOS_num_poses(0),
|
||||
_CAMPOS_pose_counter(0),
|
||||
_CAMPOS_roll_angle(0.0f),
|
||||
_CAMPOS_angle_interval(0.0f),
|
||||
_CAMPOS_pitch_angle(-90),
|
||||
_CAMPOS_updated_roll_angle(false),
|
||||
_target_system(0),
|
||||
_target_component(0),
|
||||
_trigger_pub(nullptr),
|
||||
_trigger_mode(TRIGGER_MODE_NONE),
|
||||
_cam_cap_fback(0),
|
||||
_camera_interface_mode(CAMERA_INTERFACE_MODE_GPIO),
|
||||
_camera_interface(nullptr)
|
||||
{
|
||||
// Initiate camera interface based on camera_interface_mode
|
||||
if (_camera_interface != nullptr) {
|
||||
@@ -304,14 +338,13 @@ CameraTrigger::CameraTrigger() :
|
||||
if ((_activation_time < 40.0f) &&
|
||||
(_camera_interface_mode == CAMERA_INTERFACE_MODE_GENERIC_PWM ||
|
||||
_camera_interface_mode == CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM)) {
|
||||
|
||||
_activation_time = 40.0f;
|
||||
PX4_WARN("Trigger interval too low for PWM interface, setting to 40 ms");
|
||||
param_set_no_notification(_p_activation_time, &(_activation_time));
|
||||
}
|
||||
|
||||
// Advertise critical publishers here, because we cannot advertise in interrupt context
|
||||
camera_trigger_s trigger{};
|
||||
struct camera_trigger_s trigger = {};
|
||||
|
||||
if (!_cam_cap_fback) {
|
||||
_trigger_pub = orb_advertise(ORB_ID(camera_trigger), &trigger);
|
||||
@@ -337,12 +370,13 @@ CameraTrigger::update_intervalometer()
|
||||
// control_intervalometer once on enabling/disabling trigger to schedule the calls.
|
||||
|
||||
if (_trigger_enabled && !_trigger_paused) {
|
||||
PX4_INFO("update intervalometer, trigger enabled: %d, trigger paused: %d", _trigger_enabled, _trigger_paused);
|
||||
// schedule trigger on and off calls
|
||||
hrt_call_every(&_engagecall, 0, (_interval * 1000), &CameraTrigger::engage, this);
|
||||
hrt_call_every(&_engagecall, 0, (_interval * 1000),
|
||||
(hrt_callout)&CameraTrigger::engage, this);
|
||||
|
||||
// schedule trigger on and off calls
|
||||
hrt_call_every(&_disengagecall, 0 + (_activation_time * 1000), (_interval * 1000), &CameraTrigger::disengage, this);
|
||||
hrt_call_every(&_disengagecall, 0 + (_activation_time * 1000), (_interval * 1000),
|
||||
(hrt_callout)&CameraTrigger::disengage, this);
|
||||
|
||||
}
|
||||
}
|
||||
@@ -358,6 +392,7 @@ CameraTrigger::update_distance()
|
||||
_lpos_sub.copy(&local);
|
||||
|
||||
if (local.xy_valid) {
|
||||
|
||||
// Initialize position if not done yet
|
||||
matrix::Vector2f current_position(local.x, local.y);
|
||||
|
||||
@@ -391,15 +426,14 @@ void
|
||||
CameraTrigger::enable_keep_alive(bool on)
|
||||
{
|
||||
if (on) {
|
||||
PX4_INFO("keep alive enable");
|
||||
|
||||
// schedule keep-alive up and down calls
|
||||
hrt_call_every(&_keepalivecall_up, 0, (60000 * 1000), &CameraTrigger::keep_alive_up, this);
|
||||
hrt_call_every(&_keepalivecall_up, 0, (60000 * 1000),
|
||||
(hrt_callout)&CameraTrigger::keep_alive_up, this);
|
||||
|
||||
hrt_call_every(&_keepalivecall_down, 0 + (30000 * 1000), (60000 * 1000), &CameraTrigger::keep_alive_down, this);
|
||||
hrt_call_every(&_keepalivecall_down, 0 + (30000 * 1000), (60000 * 1000),
|
||||
(hrt_callout)&CameraTrigger::keep_alive_down, this);
|
||||
|
||||
} else {
|
||||
PX4_INFO("keep alive disable");
|
||||
// cancel all calls
|
||||
hrt_cancel(&_keepalivecall_up);
|
||||
hrt_cancel(&_keepalivecall_down);
|
||||
@@ -409,25 +443,23 @@ CameraTrigger::enable_keep_alive(bool on)
|
||||
void
|
||||
CameraTrigger::toggle_power()
|
||||
{
|
||||
PX4_INFO("toggle power");
|
||||
|
||||
// schedule power toggle calls
|
||||
hrt_call_after(&_engage_turn_on_off_call, 0, &CameraTrigger::engange_turn_on_off, this);
|
||||
hrt_call_after(&_engage_turn_on_off_call, 0,
|
||||
(hrt_callout)&CameraTrigger::engange_turn_on_off, this);
|
||||
|
||||
hrt_call_after(&_disengage_turn_on_off_call, 0 + (200 * 1000), &CameraTrigger::disengage_turn_on_off, this);
|
||||
hrt_call_after(&_disengage_turn_on_off_call, 0 + (200 * 1000),
|
||||
(hrt_callout)&CameraTrigger::disengage_turn_on_off, this);
|
||||
}
|
||||
|
||||
void
|
||||
CameraTrigger::shoot_once()
|
||||
{
|
||||
PX4_INFO("shoot once");
|
||||
|
||||
// schedule trigger on and off calls
|
||||
hrt_call_after(&_engagecall, 0,
|
||||
(hrt_callout)&CameraTrigger::engage, this);
|
||||
|
||||
hrt_call_after(&_disengagecall, 0 + (_activation_time * 1000),
|
||||
&CameraTrigger::disengage, this);
|
||||
(hrt_callout)&CameraTrigger::disengage, this);
|
||||
}
|
||||
|
||||
bool
|
||||
@@ -495,13 +527,13 @@ void
|
||||
CameraTrigger::test()
|
||||
{
|
||||
vehicle_command_s vcmd{};
|
||||
vcmd.timestamp = hrt_absolute_time();
|
||||
vcmd.param5 = 1.0;
|
||||
vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_DIGICAM_CONTROL;
|
||||
vcmd.target_system = 1;
|
||||
vcmd.target_component = 1;
|
||||
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
vcmd.timestamp = hrt_absolute_time();
|
||||
vcmd_pub.publish(vcmd);
|
||||
}
|
||||
|
||||
@@ -527,7 +559,6 @@ CameraTrigger::Run()
|
||||
// Command handling
|
||||
if (updated) {
|
||||
if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_DIGICAM_CONTROL) {
|
||||
PX4_INFO("received DO_DIGICAM_CONTROL");
|
||||
|
||||
need_ack = true;
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
@@ -540,18 +571,20 @@ CameraTrigger::Run()
|
||||
if (commandParamToInt(cmd.param7) == 1) {
|
||||
// test shots are not logged or forwarded to GCS for geotagging
|
||||
_test_shot = true;
|
||||
|
||||
}
|
||||
|
||||
if (commandParamToInt((float)cmd.param5) == 1) {
|
||||
// Schedule shot
|
||||
_one_shot = true;
|
||||
|
||||
}
|
||||
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_TRIGGER_CONTROL) {
|
||||
PX4_INFO("received DO_TRIGGER_CONTROL");
|
||||
|
||||
need_ack = true;
|
||||
|
||||
if (commandParamToInt(cmd.param3) == 1) {
|
||||
@@ -577,12 +610,13 @@ CameraTrigger::Run()
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
||||
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST) {
|
||||
PX4_INFO("received DO_SET_CAM_TRIGG_DIST");
|
||||
|
||||
need_ack = true;
|
||||
|
||||
/*
|
||||
* TRANSITIONAL SUPPORT ADDED AS OF 11th MAY 2017 (v1.6 RELEASE)
|
||||
*/
|
||||
|
||||
if (cmd.param1 > 0.0f) {
|
||||
_distance = cmd.param1;
|
||||
param_set_no_notification(_p_distance, &_distance);
|
||||
@@ -615,7 +649,7 @@ CameraTrigger::Run()
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
||||
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL) {
|
||||
PX4_INFO("received DO_SET_CAM_TRIGG_INTERVAL");
|
||||
|
||||
need_ack = true;
|
||||
|
||||
if (cmd.param1 > 0.0f) {
|
||||
@@ -634,7 +668,7 @@ CameraTrigger::Run()
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
||||
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_OBLIQUE_SURVEY) {
|
||||
PX4_INFO("received OBLIQUE_SURVEY");
|
||||
|
||||
// Camera Auto Mount Pivoting Oblique Survey (CAMPOS)
|
||||
|
||||
need_ack = true;
|
||||
@@ -758,6 +792,7 @@ unknown_cmd:
|
||||
|
||||
// One shot command-based capture handling
|
||||
if (_one_shot && !_turning_on) {
|
||||
|
||||
// One-shot trigger
|
||||
shoot_once();
|
||||
_one_shot = false;
|
||||
@@ -769,44 +804,20 @@ unknown_cmd:
|
||||
|
||||
// Command ACK handling
|
||||
if (updated && need_ack) {
|
||||
PX4_INFO("acknowledging command %d, result=%d", cmd.command, cmd_result);
|
||||
vehicle_command_ack_s command_ack{};
|
||||
|
||||
command_ack.timestamp = hrt_absolute_time();
|
||||
command_ack.command = cmd.command;
|
||||
command_ack.result = (uint8_t)cmd_result;
|
||||
command_ack.target_system = cmd.source_system;
|
||||
command_ack.target_component = cmd.source_component;
|
||||
command_ack.timestamp = hrt_absolute_time();
|
||||
|
||||
_cmd_ack_pub.publish(command_ack);
|
||||
}
|
||||
|
||||
ScheduleDelayed(poll_interval_usec);
|
||||
}
|
||||
|
||||
void
|
||||
CameraTrigger::adjust_roll()
|
||||
{
|
||||
vehicle_command_s vcmd{};
|
||||
vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL;
|
||||
vcmd.target_system = _target_system;
|
||||
vcmd.target_component = _target_component;
|
||||
|
||||
//param1 of VEHICLE_CMD_DO_MOUNT_CONTROL in VEHICLE_MOUNT_MODE_MAVLINK_TARGETING mode is pitch
|
||||
vcmd.param1 = _CAMPOS_pitch_angle;
|
||||
|
||||
//param2 of VEHICLE_CMD_DO_MOUNT_CONTROL in VEHICLE_MOUNT_MODE_MAVLINK_TARGETING mode is roll
|
||||
if (++_CAMPOS_pose_counter == _CAMPOS_num_poses) {
|
||||
_CAMPOS_pose_counter = 0;
|
||||
}
|
||||
|
||||
vcmd.param2 = _CAMPOS_angle_interval * _CAMPOS_pose_counter - _CAMPOS_roll_angle;
|
||||
|
||||
vcmd.param7 = vehicle_command_s::VEHICLE_MOUNT_MODE_MAVLINK_TARGETING;
|
||||
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
vcmd.timestamp = hrt_absolute_time();
|
||||
vcmd_pub.publish(vcmd);
|
||||
}
|
||||
|
||||
void
|
||||
CameraTrigger::engage(void *arg)
|
||||
{
|
||||
@@ -830,15 +841,18 @@ CameraTrigger::engage(void *arg)
|
||||
|
||||
// Send camera trigger message. This messages indicates that we sent
|
||||
// the camera trigger request. Does not guarantee capture.
|
||||
camera_trigger_s trigger{};
|
||||
|
||||
timespec tv{};
|
||||
struct camera_trigger_s trigger = {};
|
||||
|
||||
// Set timestamp the instant after the trigger goes off
|
||||
trigger.timestamp = now;
|
||||
|
||||
timespec tv = {};
|
||||
px4_clock_gettime(CLOCK_REALTIME, &tv);
|
||||
trigger.timestamp_utc = (uint64_t) tv.tv_sec * 1000000 + tv.tv_nsec / 1000;
|
||||
|
||||
trigger.seq = trig->_trigger_seq;
|
||||
trigger.feedback = false;
|
||||
trigger.timestamp = hrt_absolute_time();
|
||||
|
||||
if (!trig->_cam_cap_fback) {
|
||||
orb_publish(ORB_ID(camera_trigger), trig->_trigger_pub, &trigger);
|
||||
@@ -921,7 +935,7 @@ static int usage()
|
||||
return 1;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int camera_trigger_main(int argc, char *argv[])
|
||||
int camera_trigger_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 2) {
|
||||
return usage();
|
||||
@@ -971,3 +985,28 @@ extern "C" __EXPORT int camera_trigger_main(int argc, char *argv[])
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void
|
||||
CameraTrigger::adjust_roll()
|
||||
{
|
||||
vehicle_command_s vcmd{};
|
||||
vcmd.timestamp = hrt_absolute_time();
|
||||
vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL;
|
||||
vcmd.target_system = _target_system;
|
||||
vcmd.target_component = _target_component;
|
||||
|
||||
//param1 of VEHICLE_CMD_DO_MOUNT_CONTROL in VEHICLE_MOUNT_MODE_MAVLINK_TARGETING mode is pitch
|
||||
vcmd.param1 = _CAMPOS_pitch_angle;
|
||||
|
||||
//param2 of VEHICLE_CMD_DO_MOUNT_CONTROL in VEHICLE_MOUNT_MODE_MAVLINK_TARGETING mode is roll
|
||||
if (++_CAMPOS_pose_counter == _CAMPOS_num_poses) {
|
||||
_CAMPOS_pose_counter = 0;
|
||||
}
|
||||
|
||||
vcmd.param2 = _CAMPOS_angle_interval * _CAMPOS_pose_counter - _CAMPOS_roll_angle;
|
||||
|
||||
vcmd.param7 = vehicle_command_s::VEHICLE_MOUNT_MODE_MAVLINK_TARGETING;
|
||||
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
vcmd_pub.publish(vcmd);
|
||||
}
|
||||
|
||||
@@ -1,8 +1,20 @@
|
||||
#include "camera_interface.h"
|
||||
#include <px4_platform_common/log.h>
|
||||
|
||||
/**
|
||||
* @file camera_interface.cpp
|
||||
*
|
||||
*/
|
||||
|
||||
CameraInterface::CameraInterface():
|
||||
_p_pin(PARAM_INVALID),
|
||||
_pins{}
|
||||
{
|
||||
}
|
||||
|
||||
void CameraInterface::get_pins()
|
||||
{
|
||||
|
||||
// Get parameter handle
|
||||
_p_pin = param_find("TRIG_PINS");
|
||||
|
||||
|
||||
@@ -12,7 +12,15 @@
|
||||
class CameraInterface
|
||||
{
|
||||
public:
|
||||
CameraInterface() = default;
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
CameraInterface();
|
||||
|
||||
/**
|
||||
* Destructor.
|
||||
*/
|
||||
virtual ~CameraInterface() = default;
|
||||
|
||||
/**
|
||||
@@ -64,8 +72,8 @@ protected:
|
||||
*/
|
||||
void get_pins();
|
||||
|
||||
param_t _p_pin{PARAM_INVALID};
|
||||
param_t _p_pin;
|
||||
|
||||
int _pins[6]{};
|
||||
int _pins[6];
|
||||
|
||||
};
|
||||
|
||||
@@ -4,12 +4,15 @@
|
||||
#include <cstring>
|
||||
#include <px4_arch/io_timer.h>
|
||||
|
||||
CameraInterfaceGPIO::CameraInterfaceGPIO()
|
||||
CameraInterfaceGPIO::CameraInterfaceGPIO():
|
||||
CameraInterface(),
|
||||
_trigger_invert(false),
|
||||
_triggers{}
|
||||
{
|
||||
_p_polarity = param_find("TRIG_POLARITY");
|
||||
|
||||
// polarity of the trigger (0 = active low, 1 = active high )
|
||||
int32_t polarity = 0;
|
||||
int32_t polarity;
|
||||
param_get(_p_polarity, &polarity);
|
||||
_trigger_invert = (polarity == 0);
|
||||
|
||||
@@ -20,6 +23,7 @@ CameraInterfaceGPIO::CameraInterfaceGPIO()
|
||||
void CameraInterfaceGPIO::setup()
|
||||
{
|
||||
for (unsigned i = 0, t = 0; i < arraySize(_pins); i++) {
|
||||
|
||||
// Pin range is from 0 to num_gpios - 1
|
||||
if (_pins[i] >= 0 && t < (int)arraySize(_triggers)) {
|
||||
uint32_t gpio = io_timer_channel_get_gpio_output(_pins[i]);
|
||||
@@ -35,9 +39,10 @@ void CameraInterfaceGPIO::trigger(bool trigger_on_true)
|
||||
bool trigger_state = trigger_on_true ^ _trigger_invert;
|
||||
|
||||
for (unsigned i = 0; i < arraySize(_triggers); i++) {
|
||||
if (_triggers[i] != 0) {
|
||||
px4_arch_gpiowrite(_triggers[i], trigger_state);
|
||||
}
|
||||
|
||||
if (_triggers[i] == 0) { break; }
|
||||
|
||||
px4_arch_gpiowrite(_triggers[i], trigger_state);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -27,11 +27,11 @@ private:
|
||||
|
||||
void setup();
|
||||
|
||||
param_t _p_polarity{PARAM_INVALID};
|
||||
param_t _p_polarity;
|
||||
|
||||
bool _trigger_invert{false};
|
||||
bool _trigger_invert;
|
||||
|
||||
uint32_t _triggers[num_gpios]{};
|
||||
uint32_t _triggers[num_gpios];
|
||||
};
|
||||
|
||||
#endif /* ifdef __PX4_NUTTX */
|
||||
|
||||
@@ -25,10 +25,10 @@ public:
|
||||
void info();
|
||||
|
||||
private:
|
||||
int32_t _pwm_camera_shoot = 0;
|
||||
int32_t _pwm_camera_neutral = 0;
|
||||
void setup();
|
||||
|
||||
int32_t _pwm_camera_shoot{0};
|
||||
int32_t _pwm_camera_neutral{0};
|
||||
};
|
||||
|
||||
#endif /* ifdef __PX4_NUTTX */
|
||||
|
||||
@@ -17,19 +17,11 @@
|
||||
#define PWM_2_CAMERA_KEEP_ALIVE 1700
|
||||
#define PWM_2_CAMERA_ON_OFF 1900
|
||||
|
||||
CameraInterfaceSeagull::CameraInterfaceSeagull()
|
||||
CameraInterfaceSeagull::CameraInterfaceSeagull():
|
||||
CameraInterface(),
|
||||
_camera_is_on(false)
|
||||
{
|
||||
//get_pins();
|
||||
|
||||
// NORA hacks
|
||||
// Set all pins as invalid
|
||||
for (unsigned i = 0; i < arraySize(_pins); i++) {
|
||||
_pins[i] = -1;
|
||||
}
|
||||
|
||||
_pins[0] = 14 - 1;
|
||||
_pins[1] = 13 - 1;
|
||||
|
||||
get_pins();
|
||||
setup();
|
||||
}
|
||||
|
||||
@@ -45,16 +37,14 @@ void CameraInterfaceSeagull::setup()
|
||||
if (_pins[i] >= 0 && _pins[i + 1] >= 0) {
|
||||
|
||||
// Initialize the interface
|
||||
uint32_t pin_bitmask = (1 << _pins[i + 1]) | (1 << _pins[i]);
|
||||
uint8_t pin_bitmask = (1 << _pins[i + 1]) | (1 << _pins[i]);
|
||||
up_pwm_trigger_init(pin_bitmask);
|
||||
|
||||
// Set both interface pins to disarmed
|
||||
int ret1 = up_pwm_trigger_set(_pins[i + 1], PWM_CAMERA_DISARMED);
|
||||
PX4_INFO("pwm trigger set %d %d=%d, ret=%d", i + 1, _pins[i + 1], PWM_CAMERA_DISARMED, ret1);
|
||||
|
||||
int ret2 = up_pwm_trigger_set(_pins[i], PWM_CAMERA_DISARMED);
|
||||
PX4_INFO("pwm trigger set %d %d=%d, ret=%d", i, _pins[i], PWM_CAMERA_DISARMED, ret2);
|
||||
up_pwm_trigger_set(_pins[i + 1], PWM_CAMERA_DISARMED);
|
||||
up_pwm_trigger_set(_pins[i], PWM_CAMERA_DISARMED);
|
||||
|
||||
// We only support 2 consecutive pins while using the Seagull MAP2
|
||||
return;
|
||||
}
|
||||
}
|
||||
@@ -64,6 +54,7 @@ void CameraInterfaceSeagull::setup()
|
||||
|
||||
void CameraInterfaceSeagull::trigger(bool trigger_on_true)
|
||||
{
|
||||
|
||||
if (!_camera_is_on) {
|
||||
return;
|
||||
}
|
||||
@@ -79,6 +70,7 @@ void CameraInterfaceSeagull::trigger(bool trigger_on_true)
|
||||
void CameraInterfaceSeagull::send_keep_alive(bool enable)
|
||||
{
|
||||
// This should alternate between enable and !enable to keep the camera alive
|
||||
|
||||
if (!_camera_is_on) {
|
||||
return;
|
||||
}
|
||||
@@ -93,7 +85,9 @@ void CameraInterfaceSeagull::send_keep_alive(bool enable)
|
||||
|
||||
void CameraInterfaceSeagull::send_toggle_power(bool enable)
|
||||
{
|
||||
|
||||
// This should alternate between enable and !enable to toggle camera power
|
||||
|
||||
for (unsigned i = 0; i < arraySize(_pins); i = i + 2) {
|
||||
if (_pins[i] >= 0 && _pins[i + 1] >= 0) {
|
||||
// Set channel 1 to neutral
|
||||
@@ -103,9 +97,7 @@ void CameraInterfaceSeagull::send_toggle_power(bool enable)
|
||||
}
|
||||
}
|
||||
|
||||
if (!enable) {
|
||||
_camera_is_on = !_camera_is_on;
|
||||
}
|
||||
if (!enable) { _camera_is_on = !_camera_is_on; }
|
||||
}
|
||||
|
||||
void CameraInterfaceSeagull::info()
|
||||
|
||||
@@ -33,7 +33,7 @@ public:
|
||||
private:
|
||||
void setup();
|
||||
|
||||
bool _camera_is_on{false};
|
||||
bool _camera_is_on;
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -215,9 +215,6 @@ typedef uint16_t servo_position_t;
|
||||
/** force safety switch on (to enable use of safety switch) */
|
||||
#define PWM_SERVO_SET_FORCE_SAFETY_ON _PX4_IOC(_PWM_SERVO_BASE, 28)
|
||||
|
||||
/** setup OVERRIDE_IMMEDIATE behaviour on FMU fail */
|
||||
#define PWM_SERVO_SET_OVERRIDE_IMMEDIATE _PX4_IOC(_PWM_SERVO_BASE, 32)
|
||||
|
||||
/** set auxillary output mode. These correspond to enum Mode in px4fmu/fmu.cpp */
|
||||
#define PWM_SERVO_MODE_NONE 0
|
||||
#define PWM_SERVO_MODE_1PWM 1
|
||||
|
||||
@@ -1,80 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file drv_rc_input.h
|
||||
*
|
||||
* R/C input interface.
|
||||
*/
|
||||
|
||||
#ifndef _DRV_RC_INPUT_H
|
||||
#define _DRV_RC_INPUT_H
|
||||
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <uORB/topics/input_rc.h>
|
||||
|
||||
#include "drv_orb_dev.h"
|
||||
|
||||
/**
|
||||
* Path for the default R/C input device.
|
||||
*
|
||||
* Note that on systems with more than one R/C input path (e.g.
|
||||
* PX4FMU with PX4IO connected) there may be other devices that
|
||||
* respond to this protocol.
|
||||
*
|
||||
* Input data may be obtained by subscribing to the input_rc
|
||||
* object, or by poll/reading from the device.
|
||||
*/
|
||||
#define RC_INPUT0_DEVICE_PATH "/dev/input_rc0"
|
||||
|
||||
/**
|
||||
* Maximum RSSI value
|
||||
*/
|
||||
#define RC_INPUT_RSSI_MAX 100
|
||||
|
||||
/**
|
||||
* Input signal type, value is a control position from zero to 100
|
||||
* percent.
|
||||
*/
|
||||
typedef uint16_t rc_input_t;
|
||||
|
||||
#define _RC_INPUT_BASE 0x2b00
|
||||
|
||||
/** Enable RSSI input via ADC */
|
||||
#define RC_INPUT_ENABLE_RSSI_ANALOG _IOC(_RC_INPUT_BASE, 1)
|
||||
|
||||
/** Enable RSSI input via PWM signal */
|
||||
#define RC_INPUT_ENABLE_RSSI_PWM _IOC(_RC_INPUT_BASE, 2)
|
||||
|
||||
#endif /* _DRV_RC_INPUT_H */
|
||||
@@ -1113,26 +1113,16 @@ int PWMOut::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
|
||||
case PWM_SERVO_GET(13):
|
||||
case PWM_SERVO_GET(12):
|
||||
case PWM_SERVO_GET(11):
|
||||
case PWM_SERVO_GET(10):
|
||||
case PWM_SERVO_GET(9):
|
||||
case PWM_SERVO_GET(8):
|
||||
if (_mode < MODE_14PWM) {
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
|
||||
#endif
|
||||
#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 12
|
||||
|
||||
// FALLTHROUGH
|
||||
case PWM_SERVO_GET(11):
|
||||
case PWM_SERVO_GET(10):
|
||||
case PWM_SERVO_GET(9):
|
||||
case PWM_SERVO_GET(8):
|
||||
if (_mode < MODE_12PWM) {
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
|
||||
// FALLTHROUGH
|
||||
#endif
|
||||
#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 8
|
||||
|
||||
/* FALLTHROUGH */
|
||||
|
||||
@@ -35,6 +35,10 @@ px4_add_module(
|
||||
MAIN px4io
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
-Wno-error
|
||||
#-DDEBUG_BUILD
|
||||
STACK_MAIN
|
||||
10000
|
||||
SRCS
|
||||
px4io.cpp
|
||||
px4io_serial.cpp
|
||||
@@ -42,7 +46,7 @@ px4_add_module(
|
||||
DEPENDS
|
||||
arch_px4io_serial
|
||||
circuit_breaker
|
||||
mixer
|
||||
mixer_module
|
||||
)
|
||||
|
||||
# include the px4io binary in ROMFS
|
||||
|
||||
+519
-1566
File diff suppressed because it is too large
Load Diff
@@ -47,9 +47,10 @@
|
||||
*
|
||||
* Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up.
|
||||
*
|
||||
* @boolean
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @value 0 IO disabled
|
||||
* @value 1 IO default (RC & PWM output)
|
||||
* @value 2 RC only
|
||||
* @value 3 PWM output only
|
||||
* @reboot_required true
|
||||
* @group System
|
||||
*/
|
||||
|
||||
@@ -51,24 +51,14 @@ device::Device
|
||||
|
||||
PX4IO_serial::PX4IO_serial() :
|
||||
Device("PX4IO_serial"),
|
||||
_pc_txns(perf_alloc(PC_ELAPSED, "io_txns")),
|
||||
#if 0
|
||||
_pc_retries(perf_alloc(PC_COUNT, "io_retries ")),
|
||||
_pc_timeouts(perf_alloc(PC_COUNT, "io_timeouts ")),
|
||||
_pc_crcerrs(perf_alloc(PC_COUNT, "io_crcerrs ")),
|
||||
_pc_protoerrs(perf_alloc(PC_COUNT, "io_protoerrs")),
|
||||
_pc_uerrs(perf_alloc(PC_COUNT, "io_uarterrs ")),
|
||||
_pc_idle(perf_alloc(PC_COUNT, "io_idle ")),
|
||||
_pc_badidle(perf_alloc(PC_COUNT, "io_badidle ")),
|
||||
#else
|
||||
_pc_retries(nullptr),
|
||||
_pc_timeouts(nullptr),
|
||||
_pc_crcerrs(nullptr),
|
||||
_pc_protoerrs(nullptr),
|
||||
_pc_uerrs(nullptr),
|
||||
_pc_idle(nullptr),
|
||||
_pc_badidle(nullptr),
|
||||
#endif
|
||||
_pc_txns(perf_alloc(PC_ELAPSED, MODULE_NAME": txns")),
|
||||
_pc_retries(perf_alloc(PC_COUNT, MODULE_NAME": retries")),
|
||||
_pc_timeouts(perf_alloc(PC_COUNT, MODULE_NAME": timeouts")),
|
||||
_pc_crcerrs(perf_alloc(PC_COUNT, MODULE_NAME": crcerrs")),
|
||||
_pc_protoerrs(perf_alloc(PC_COUNT, MODULE_NAME": protoerrs")),
|
||||
_pc_uerrs(perf_alloc(PC_COUNT, MODULE_NAME": uarterrs")),
|
||||
_pc_idle(perf_alloc(PC_COUNT, MODULE_NAME": idle")),
|
||||
_pc_badidle(perf_alloc(PC_COUNT, MODULE_NAME": badidle")),
|
||||
_bus_semaphore(SEM_INITIALIZER(0))
|
||||
{
|
||||
g_interface = this;
|
||||
|
||||
@@ -355,9 +355,8 @@ int
|
||||
PX4IO_Uploader::get_sync(unsigned timeout)
|
||||
{
|
||||
uint8_t c[2];
|
||||
int ret;
|
||||
|
||||
ret = recv_byte_with_timeout(c, timeout);
|
||||
int ret = recv_byte_with_timeout(c, timeout);
|
||||
|
||||
if (ret != OK) {
|
||||
return ret;
|
||||
@@ -395,13 +394,11 @@ PX4IO_Uploader::sync()
|
||||
int
|
||||
PX4IO_Uploader::get_info(int param, uint32_t &val)
|
||||
{
|
||||
int ret;
|
||||
|
||||
send(PROTO_GET_DEVICE);
|
||||
send(param);
|
||||
send(PROTO_EOC);
|
||||
|
||||
ret = recv_bytes((uint8_t *)&val, sizeof(val));
|
||||
int ret = recv_bytes((uint8_t *)&val, sizeof(val));
|
||||
|
||||
if (ret != OK) {
|
||||
return ret;
|
||||
@@ -419,7 +416,6 @@ PX4IO_Uploader::erase()
|
||||
return get_sync(10000); /* allow 10s timeout */
|
||||
}
|
||||
|
||||
|
||||
static int read_with_retry(int fd, void *buf, size_t n)
|
||||
{
|
||||
int ret;
|
||||
|
||||
@@ -480,7 +480,7 @@ void RCInput::Run()
|
||||
|
||||
for (unsigned i = 0; i < (unsigned)newBytes; i++) {
|
||||
/* set updated flag if one complete packet was parsed */
|
||||
st24_rssi = RC_INPUT_RSSI_MAX;
|
||||
st24_rssi = input_rc_s::RSSI_MAX;
|
||||
rc_updated = (OK == st24_decode(_rcs_buf[i], &st24_rssi, &lost_count,
|
||||
&_raw_rc_count, _raw_rc_values, input_rc_s::RC_INPUT_MAX_CHANNELS));
|
||||
}
|
||||
@@ -529,7 +529,7 @@ void RCInput::Run()
|
||||
|
||||
for (unsigned i = 0; i < (unsigned)newBytes; i++) {
|
||||
/* set updated flag if one complete packet was parsed */
|
||||
sumd_rssi = RC_INPUT_RSSI_MAX;
|
||||
sumd_rssi = input_rc_s::RSSI_MAX;
|
||||
rc_updated = (OK == sumd_decode(_rcs_buf[i], &sumd_rssi, &rx_count,
|
||||
&_raw_rc_count, _raw_rc_values, input_rc_s::RC_INPUT_MAX_CHANNELS, &sumd_failsafe));
|
||||
}
|
||||
|
||||
@@ -38,7 +38,6 @@
|
||||
#include <board_config.h>
|
||||
#include <drivers/drv_adc.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <lib/rc/crsf.h>
|
||||
#include <lib/rc/ghst.h>
|
||||
|
||||
@@ -46,7 +46,6 @@
|
||||
#include <px4_platform_common/getopt.h>
|
||||
|
||||
#include <lib/rc/dsm.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
@@ -32,3 +32,4 @@
|
||||
############################################################################
|
||||
|
||||
px4_add_library(mixer_module mixer_module.cpp)
|
||||
target_link_libraries(mixer_module PRIVATE output_limit)
|
||||
|
||||
@@ -89,7 +89,11 @@ MixingOutput::~MixingOutput()
|
||||
void MixingOutput::printStatus() const
|
||||
{
|
||||
perf_print_counter(_control_latency_perf);
|
||||
PX4_INFO("Switched to rate_ctrl work queue: %i", (int)_wq_switched);
|
||||
|
||||
if (_wq_switched) {
|
||||
PX4_INFO("Switched to rate_ctrl work queue");
|
||||
}
|
||||
|
||||
PX4_INFO("Mixer loaded: %s", _mixers ? "yes" : "no");
|
||||
PX4_INFO("Driver instance: %i", _driver_instance);
|
||||
|
||||
|
||||
+3
-9
@@ -50,6 +50,7 @@
|
||||
#include "sbus.h"
|
||||
#include "common_rc.h"
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <lib/mathlib/mathlib.h>
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
@@ -689,13 +690,6 @@ sbus_decode(uint64_t frame_time, uint8_t *frame, uint16_t *values, uint16_t *num
|
||||
*/
|
||||
void sbus1_set_output_rate_hz(uint16_t rate_hz)
|
||||
{
|
||||
if (rate_hz > SBUS1_MAX_RATE_HZ) {
|
||||
rate_hz = SBUS1_MAX_RATE_HZ;
|
||||
}
|
||||
|
||||
if (rate_hz < SBUS1_MIN_RATE_HZ) {
|
||||
rate_hz = SBUS1_MIN_RATE_HZ;
|
||||
}
|
||||
|
||||
sbus1_frame_delay = (1000U * 1000U) / rate_hz;
|
||||
sbus1_frame_delay = (1000U * 1000U) / math::constrain(rate_hz, (uint16_t)SBUS1_MIN_RATE_HZ,
|
||||
(uint16_t)SBUS1_MAX_RATE_HZ);
|
||||
}
|
||||
|
||||
@@ -242,7 +242,7 @@ bool PreFlightCheck::ekf2CheckSensorBias(orb_advert_t *mavlink_log_pub, const bo
|
||||
|
||||
// check accelerometer bias estimates
|
||||
if (bias.accel_bias_valid) {
|
||||
const float ekf_ab_test_limit = 0.75f * bias.accel_bias_limit;
|
||||
const float ekf_ab_test_limit = 0.5f * bias.accel_bias_limit;
|
||||
|
||||
for (uint8_t axis_index = 0; axis_index < 3; axis_index++) {
|
||||
// allow for higher uncertainty in estimates for axes that are less observable to prevent false positives
|
||||
@@ -263,7 +263,7 @@ bool PreFlightCheck::ekf2CheckSensorBias(orb_advert_t *mavlink_log_pub, const bo
|
||||
|
||||
// check gyro bias estimates
|
||||
if (bias.gyro_bias_valid) {
|
||||
const float ekf_gb_test_limit = 0.75f * bias.gyro_bias_limit;
|
||||
const float ekf_gb_test_limit = 0.5f * bias.gyro_bias_limit;
|
||||
|
||||
for (uint8_t axis_index = 0; axis_index < 3; axis_index++) {
|
||||
// allow for higher uncertainty in estimates for axes that are less observable to prevent false positives
|
||||
|
||||
@@ -94,7 +94,7 @@ bool PreFlightCheck::preArmCheck(orb_advert_t *mavlink_log_pub, const vehicle_st
|
||||
}
|
||||
}
|
||||
|
||||
if (arm_requirements.global_position && !status_flags.circuit_breaker_engaged_posfailure_check) {
|
||||
if (arm_requirements.global_position) {
|
||||
|
||||
if (!status_flags.condition_global_position_valid) {
|
||||
if (prearm_ok) {
|
||||
|
||||
@@ -2300,7 +2300,7 @@ Commander::run()
|
||||
}
|
||||
|
||||
// evaluate the main state machine according to mode switches
|
||||
if (set_main_state(&_status_changed) == TRANSITION_CHANGED) {
|
||||
if (set_main_state() == TRANSITION_CHANGED) {
|
||||
// play tune on mode change only if armed, blink LED always
|
||||
tune_positive(_armed.armed);
|
||||
_status_changed = true;
|
||||
@@ -2873,29 +2873,7 @@ Commander::control_status_leds(bool changed, const uint8_t battery_warning)
|
||||
_leds_counter++;
|
||||
}
|
||||
|
||||
transition_result_t
|
||||
Commander::set_main_state(bool *changed)
|
||||
{
|
||||
if (_safety.override_available && _safety.override_enabled) {
|
||||
return set_main_state_override_on(changed);
|
||||
|
||||
} else {
|
||||
return set_main_state_rc();
|
||||
}
|
||||
}
|
||||
|
||||
transition_result_t
|
||||
Commander::set_main_state_override_on(bool *changed)
|
||||
{
|
||||
const transition_result_t res = main_state_transition(_status, commander_state_s::MAIN_STATE_MANUAL, _status_flags,
|
||||
&_internal_state);
|
||||
*changed = (res == TRANSITION_CHANGED);
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
transition_result_t
|
||||
Commander::set_main_state_rc()
|
||||
transition_result_t Commander::set_main_state()
|
||||
{
|
||||
if ((_manual_control_switches.timestamp == 0)
|
||||
|| (_manual_control_switches.timestamp == _last_manual_control_switches.timestamp)) {
|
||||
@@ -2912,15 +2890,8 @@ Commander::set_main_state_rc()
|
||||
bool should_evaluate_rc_mode_switch =
|
||||
(_last_manual_control_switches.offboard_switch != _manual_control_switches.offboard_switch)
|
||||
|| (_last_manual_control_switches.return_switch != _manual_control_switches.return_switch)
|
||||
|| (_last_manual_control_switches.mode_switch != _manual_control_switches.mode_switch)
|
||||
|| (_last_manual_control_switches.acro_switch != _manual_control_switches.acro_switch)
|
||||
|| (_last_manual_control_switches.rattitude_switch != _manual_control_switches.rattitude_switch)
|
||||
|| (_last_manual_control_switches.posctl_switch != _manual_control_switches.posctl_switch)
|
||||
|| (_last_manual_control_switches.loiter_switch != _manual_control_switches.loiter_switch)
|
||||
|| (_last_manual_control_switches.mode_slot != _manual_control_switches.mode_slot)
|
||||
|| (_last_manual_control_switches.stab_switch != _manual_control_switches.stab_switch)
|
||||
|| (_last_manual_control_switches.man_switch != _manual_control_switches.man_switch);
|
||||
|
||||
|| (_last_manual_control_switches.mode_slot != _manual_control_switches.mode_slot);
|
||||
|
||||
if (_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
|
||||
// if already armed don't evaluate first time RC
|
||||
@@ -3137,147 +3108,6 @@ Commander::set_main_state_rc()
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return res;
|
||||
|
||||
} else if (_manual_control_switches.mode_switch != manual_control_switches_s::SWITCH_POS_NONE) {
|
||||
/* offboard and RTL switches off or denied, check main mode switch */
|
||||
switch (_manual_control_switches.mode_switch) {
|
||||
case manual_control_switches_s::SWITCH_POS_NONE:
|
||||
res = TRANSITION_NOT_CHANGED;
|
||||
break;
|
||||
|
||||
case manual_control_switches_s::SWITCH_POS_OFF: // MANUAL
|
||||
if (_manual_control_switches.stab_switch == manual_control_switches_s::SWITCH_POS_NONE &&
|
||||
_manual_control_switches.man_switch == manual_control_switches_s::SWITCH_POS_NONE) {
|
||||
/*
|
||||
* Legacy mode:
|
||||
* Acro switch being used as stabilized switch in FW.
|
||||
*/
|
||||
if (_manual_control_switches.acro_switch == manual_control_switches_s::SWITCH_POS_ON) {
|
||||
/* manual mode is stabilized already for multirotors, so switch to acro
|
||||
* for any non-manual mode
|
||||
*/
|
||||
if (_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && !_status.is_vtol) {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_ACRO, _status_flags, &_internal_state);
|
||||
|
||||
} else if (_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_STAB, _status_flags, &_internal_state);
|
||||
|
||||
} else {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_MANUAL, _status_flags, &_internal_state);
|
||||
}
|
||||
|
||||
} else if (_manual_control_switches.rattitude_switch == manual_control_switches_s::SWITCH_POS_ON) {
|
||||
/* Similar to acro transitions for multirotors. FW aircraft don't need a
|
||||
* rattitude mode.*/
|
||||
if (_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_RATTITUDE, _status_flags, &_internal_state);
|
||||
|
||||
} else {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_STAB, _status_flags, &_internal_state);
|
||||
}
|
||||
|
||||
} else {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_MANUAL, _status_flags, &_internal_state);
|
||||
}
|
||||
|
||||
} else {
|
||||
/* New mode:
|
||||
* - Acro is Acro
|
||||
* - Manual is not default anymore when the manual switch is assigned
|
||||
*/
|
||||
if (_manual_control_switches.man_switch == manual_control_switches_s::SWITCH_POS_ON) {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_MANUAL, _status_flags, &_internal_state);
|
||||
|
||||
} else if (_manual_control_switches.acro_switch == manual_control_switches_s::SWITCH_POS_ON) {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_ACRO, _status_flags, &_internal_state);
|
||||
|
||||
} else if (_manual_control_switches.rattitude_switch == manual_control_switches_s::SWITCH_POS_ON) {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_RATTITUDE, _status_flags, &_internal_state);
|
||||
|
||||
} else if (_manual_control_switches.stab_switch == manual_control_switches_s::SWITCH_POS_ON) {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_STAB, _status_flags, &_internal_state);
|
||||
|
||||
} else if (_manual_control_switches.man_switch == manual_control_switches_s::SWITCH_POS_NONE) {
|
||||
// default to MANUAL when no manual switch is set
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_MANUAL, _status_flags, &_internal_state);
|
||||
|
||||
} else {
|
||||
// default to STAB when the manual switch is assigned (but off)
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_STAB, _status_flags, &_internal_state);
|
||||
}
|
||||
}
|
||||
|
||||
// TRANSITION_DENIED is not possible here
|
||||
break;
|
||||
|
||||
case manual_control_switches_s::SWITCH_POS_MIDDLE: // ASSIST
|
||||
if (_manual_control_switches.posctl_switch == manual_control_switches_s::SWITCH_POS_ON) {
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_POSCTL, _status_flags, &_internal_state);
|
||||
|
||||
if (res != TRANSITION_DENIED) {
|
||||
break; // changed successfully or already in this state
|
||||
}
|
||||
|
||||
print_reject_mode("POSITION CONTROL");
|
||||
}
|
||||
|
||||
// fallback to ALTCTL
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_ALTCTL, _status_flags, &_internal_state);
|
||||
|
||||
if (res != TRANSITION_DENIED) {
|
||||
break; // changed successfully or already in this mode
|
||||
}
|
||||
|
||||
if (_manual_control_switches.posctl_switch != manual_control_switches_s::SWITCH_POS_ON) {
|
||||
print_reject_mode("ALTITUDE CONTROL");
|
||||
}
|
||||
|
||||
// fallback to MANUAL
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_MANUAL, _status_flags, &_internal_state);
|
||||
// TRANSITION_DENIED is not possible here
|
||||
break;
|
||||
|
||||
case manual_control_switches_s::SWITCH_POS_ON: // AUTO
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_AUTO_MISSION, _status_flags, &_internal_state);
|
||||
|
||||
if (res != TRANSITION_DENIED) {
|
||||
break; // changed successfully or already in this state
|
||||
}
|
||||
|
||||
print_reject_mode("AUTO MISSION");
|
||||
|
||||
// fallback to LOITER if home position not set
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_AUTO_LOITER, _status_flags, &_internal_state);
|
||||
|
||||
if (res != TRANSITION_DENIED) {
|
||||
break; // changed successfully or already in this state
|
||||
}
|
||||
|
||||
// fallback to POSCTL
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_POSCTL, _status_flags, &_internal_state);
|
||||
|
||||
if (res != TRANSITION_DENIED) {
|
||||
break; // changed successfully or already in this state
|
||||
}
|
||||
|
||||
// fallback to ALTCTL
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_ALTCTL, _status_flags, &_internal_state);
|
||||
|
||||
if (res != TRANSITION_DENIED) {
|
||||
break; // changed successfully or already in this state
|
||||
}
|
||||
|
||||
// fallback to MANUAL
|
||||
res = main_state_transition(_status, commander_state_s::MAIN_STATE_MANUAL, _status_flags, &_internal_state);
|
||||
// TRANSITION_DENIED is not possible here
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return res;
|
||||
@@ -3359,9 +3189,6 @@ Commander::update_control_mode()
|
||||
/* set vehicle_control_mode according to set_navigation_state */
|
||||
_vehicle_control_mode.flag_armed = _armed.armed;
|
||||
|
||||
_vehicle_control_mode.flag_external_manual_override_ok =
|
||||
(_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && !_status.is_vtol);
|
||||
|
||||
switch (_status.nav_state) {
|
||||
case vehicle_status_s::NAVIGATION_STATE_MANUAL:
|
||||
_vehicle_control_mode.flag_control_manual_enabled = true;
|
||||
@@ -3401,10 +3228,6 @@ Commander::update_control_mode()
|
||||
break;
|
||||
|
||||
case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL:
|
||||
/* override is not ok for the RTL and recovery mode */
|
||||
_vehicle_control_mode.flag_external_manual_override_ok = false;
|
||||
|
||||
/* fallthrough */
|
||||
case vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET:
|
||||
case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND:
|
||||
case vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL:
|
||||
|
||||
@@ -173,14 +173,8 @@ private:
|
||||
|
||||
void UpdateEstimateValidity();
|
||||
|
||||
// Set the main system state based on RC and override device inputs
|
||||
transition_result_t set_main_state(bool *changed);
|
||||
|
||||
// Enable override (manual reversion mode) on the system
|
||||
transition_result_t set_main_state_override_on(bool *changed);
|
||||
|
||||
// Set the system main state based on the current RC inputs
|
||||
transition_result_t set_main_state_rc();
|
||||
transition_result_t set_main_state();
|
||||
|
||||
bool shutdown_if_allowed();
|
||||
|
||||
|
||||
@@ -307,8 +307,7 @@ PARAM_DEFINE_FLOAT(COM_DISARM_PRFLT, 10.0f);
|
||||
* The default allows to arm the vehicle without GPS signal.
|
||||
*
|
||||
* @group Commander
|
||||
* @value 0 Allow arming without GPS
|
||||
* @value 1 Require GPS lock to arm
|
||||
* @boolean
|
||||
*/
|
||||
PARAM_DEFINE_INT32(COM_ARM_WO_GPS, 1);
|
||||
|
||||
@@ -686,7 +685,7 @@ PARAM_DEFINE_INT32(COM_POSCTL_NAVL, 0);
|
||||
/**
|
||||
* Require arm authorization to arm
|
||||
*
|
||||
* By default off. The default allows to arm the vehicle without a arm authorization.
|
||||
* The default allows to arm the vehicle without a arm authorization.
|
||||
*
|
||||
* @group Commander
|
||||
* @boolean
|
||||
|
||||
@@ -108,8 +108,8 @@ PARAM_DEFINE_INT32(SDLOG_MISSION, 0);
|
||||
* Logging topic profile (integer bitmask).
|
||||
*
|
||||
* This integer bitmask controls the set and rates of logged topics.
|
||||
* The default allows for general log analysis while keeping the
|
||||
* log file size reasonably small.
|
||||
* The default allows for general log analysis and estimator replay, while
|
||||
* keeping the log file size reasonably small.
|
||||
*
|
||||
* Enabling multiple sets leads to higher bandwidth requirements and larger log
|
||||
* files.
|
||||
|
||||
@@ -1476,9 +1476,6 @@ Mavlink::update_radio_status(const radio_status_s &radio_status)
|
||||
/* this indicates spare bandwidth, increase by 2.5% */
|
||||
_radio_status_mult *= 1.025f;
|
||||
}
|
||||
|
||||
/* Constrain radio status multiplier between 1% and 100% to allow recovery */
|
||||
_radio_status_mult = math::constrain(_radio_status_mult, 0.01f, 1.0f);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -518,8 +518,6 @@ public:
|
||||
|
||||
static hrt_abstime &get_first_start_time() { return _first_start_time; }
|
||||
|
||||
bool radio_status_critical() const { return _radio_status_critical; }
|
||||
|
||||
private:
|
||||
int _instance_id{0};
|
||||
|
||||
|
||||
@@ -329,8 +329,7 @@ MavlinkParametersManager::send()
|
||||
int i = 0;
|
||||
|
||||
// Send while burst is not exceeded, we still have buffer space and still something to send
|
||||
while ((i++ < max_num_to_send) && (_mavlink->get_free_tx_buf() >= get_size()) && !_mavlink->radio_status_critical()
|
||||
&& send_params()) {}
|
||||
while ((i++ < max_num_to_send) && (_mavlink->get_free_tx_buf() >= get_size()) && send_params()) {}
|
||||
}
|
||||
|
||||
bool
|
||||
@@ -391,8 +390,7 @@ MavlinkParametersManager::send_untransmitted()
|
||||
break;
|
||||
}
|
||||
}
|
||||
} while ((_mavlink->get_free_tx_buf() >= get_size()) && !_mavlink->radio_status_critical()
|
||||
&& (_param_update_index < (int) param_count()));
|
||||
} while ((_mavlink->get_free_tx_buf() >= get_size()) && (_param_update_index < (int) param_count()));
|
||||
|
||||
// Flag work as done once all params have been sent
|
||||
if (_param_update_index >= (int) param_count()) {
|
||||
|
||||
@@ -43,7 +43,6 @@
|
||||
#include <airspeed/airspeed.h>
|
||||
#include <commander/px4_custom_mode.h>
|
||||
#include <conversion/rotation.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
#include <ecl/geo/geo.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
@@ -2015,7 +2014,7 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg)
|
||||
// metadata
|
||||
rc.timestamp = hrt_absolute_time();
|
||||
rc.timestamp_last_signal = rc.timestamp;
|
||||
rc.rssi = RC_INPUT_RSSI_MAX;
|
||||
rc.rssi = input_rc_s::RSSI_MAX;
|
||||
rc.rc_failsafe = false;
|
||||
rc.rc_lost = false;
|
||||
rc.rc_lost_frame_count = 0;
|
||||
@@ -2087,7 +2086,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
|
||||
rc.rc_total_frame_count = 1;
|
||||
rc.rc_ppm_frame_length = 0;
|
||||
rc.input_source = input_rc_s::RC_INPUT_SOURCE_MAVLINK;
|
||||
rc.rssi = RC_INPUT_RSSI_MAX;
|
||||
rc.rssi = input_rc_s::RSSI_MAX;
|
||||
|
||||
rc.values[0] = man.x / 2 + 1500; // roll
|
||||
rc.values[1] = man.y / 2 + 1500; // pitch
|
||||
|
||||
@@ -78,11 +78,8 @@ private:
|
||||
if (_manual_control_switches_sub.copy(&manual_control_switches)) {
|
||||
unsigned shift = 2;
|
||||
msg.buttons = 0;
|
||||
msg.buttons |= (manual_control_switches.mode_switch << (shift * 0));
|
||||
msg.buttons |= (manual_control_switches.return_switch << (shift * 1));
|
||||
msg.buttons |= (manual_control_switches.posctl_switch << (shift * 2));
|
||||
msg.buttons |= (manual_control_switches.loiter_switch << (shift * 3));
|
||||
msg.buttons |= (manual_control_switches.acro_switch << (shift * 4));
|
||||
msg.buttons |= (manual_control_switches.offboard_switch << (shift * 5));
|
||||
msg.buttons |= (manual_control_switches.kill_switch << (shift * 6));
|
||||
}
|
||||
|
||||
@@ -257,8 +257,6 @@ void RTL::on_activation()
|
||||
|
||||
const vehicle_global_position_s &global_position = *_navigator->get_global_position();
|
||||
|
||||
_rtl_loiter_rad = _param_rtl_loiter_rad.get();
|
||||
|
||||
if (_navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
|
||||
_rtl_alt = calculate_return_alt_from_cone_half_angle((float)_param_rtl_cone_half_angle_deg.get());
|
||||
|
||||
@@ -412,10 +410,6 @@ void RTL::set_rtl_item()
|
||||
_mission_item.yaw = _destination.yaw;
|
||||
}
|
||||
|
||||
if (_navigator->get_vstatus()->is_vtol) {
|
||||
_mission_item.loiter_radius = _rtl_loiter_rad;
|
||||
}
|
||||
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.time_inside = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
@@ -459,24 +453,6 @@ void RTL::set_rtl_item()
|
||||
break;
|
||||
}
|
||||
|
||||
case RTL_STATE_HEAD_TO_CENTER: {
|
||||
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
|
||||
|
||||
_mission_item.lat = _destination.lat;
|
||||
_mission_item.lon = _destination.lon;
|
||||
_mission_item.altitude = loiter_altitude;
|
||||
_mission_item.altitude_is_relative = false;
|
||||
_mission_item.yaw = get_bearing_to_next_waypoint(gpos.lat, gpos.lon, _mission_item.lat, _mission_item.lon);
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.time_inside = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
// Disable previous setpoint to prevent drift.
|
||||
pos_sp_triplet->previous.valid = false;
|
||||
break;
|
||||
}
|
||||
|
||||
case RTL_STATE_TRANSITION_TO_MC: {
|
||||
set_vtol_transition_item(&_mission_item, vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC);
|
||||
break;
|
||||
@@ -578,7 +554,7 @@ void RTL::advance_rtl()
|
||||
_rtl_state = RTL_STATE_LOITER;
|
||||
|
||||
} else if (vtol_in_fw_mode) {
|
||||
_rtl_state = RTL_STATE_HEAD_TO_CENTER;
|
||||
_rtl_state = RTL_STATE_TRANSITION_TO_MC;
|
||||
|
||||
} else {
|
||||
_rtl_state = RTL_STATE_LAND;
|
||||
@@ -597,12 +573,6 @@ void RTL::advance_rtl()
|
||||
_rtl_state = RTL_STATE_LAND;
|
||||
break;
|
||||
|
||||
case RTL_STATE_HEAD_TO_CENTER:
|
||||
|
||||
_rtl_state = RTL_STATE_TRANSITION_TO_MC;
|
||||
|
||||
break;
|
||||
|
||||
case RTL_STATE_TRANSITION_TO_MC:
|
||||
|
||||
_rtl_state = RTL_MOVE_TO_LAND_HOVER_VTOL;
|
||||
|
||||
@@ -121,7 +121,6 @@ private:
|
||||
RTL_MOVE_TO_LAND_HOVER_VTOL,
|
||||
RTL_STATE_LAND,
|
||||
RTL_STATE_LANDED,
|
||||
RTL_STATE_HEAD_TO_CENTER,
|
||||
} _rtl_state{RTL_STATE_NONE};
|
||||
|
||||
struct RTLPosition {
|
||||
@@ -149,7 +148,6 @@ private:
|
||||
|
||||
float _rtl_alt{0.0f}; // AMSL altitude at which the vehicle should return to the home position
|
||||
bool _rtl_alt_min{false};
|
||||
float _rtl_loiter_rad{50.0f}; // radius at which a fixed wing would loiter while descending
|
||||
bool _climb_and_return_done{false}; // this flag is set to true if RTL is active and we are past the climb state and return state
|
||||
bool _deny_mission_landing{false};
|
||||
|
||||
@@ -161,8 +159,7 @@ private:
|
||||
(ParamInt<px4::params::RTL_TYPE>) _param_rtl_type,
|
||||
(ParamInt<px4::params::RTL_CONE_ANG>) _param_rtl_cone_half_angle_deg,
|
||||
(ParamFloat<px4::params::RTL_FLT_TIME>) _param_rtl_flt_time,
|
||||
(ParamInt<px4::params::RTL_PLD_MD>) _param_rtl_pld_md,
|
||||
(ParamFloat<px4::params::RTL_LOITER_RAD>) _param_rtl_loiter_rad
|
||||
(ParamInt<px4::params::RTL_PLD_MD>) _param_rtl_pld_md
|
||||
)
|
||||
|
||||
// These need to point at different parameters depending on vehicle type.
|
||||
|
||||
@@ -159,17 +159,3 @@ PARAM_DEFINE_FLOAT(RTL_FLT_TIME, 15);
|
||||
* @group Return To Land
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RTL_PLD_MD, 0);
|
||||
|
||||
/**
|
||||
* Loiter radius for rtl descend
|
||||
*
|
||||
* Set the radius for loitering to a safe altitude for VTOL transition.
|
||||
*
|
||||
* @unit m
|
||||
* @min 25
|
||||
* @max 1000
|
||||
* @decimal 1
|
||||
* @increment 0.5
|
||||
* @group Return Mode
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 50.0f);
|
||||
|
||||
@@ -50,9 +50,7 @@ target_link_libraries(px4iofirmware
|
||||
nuttx_apps
|
||||
nuttx_arch
|
||||
nuttx_c
|
||||
mixer
|
||||
rc
|
||||
output_limit
|
||||
)
|
||||
|
||||
if(PX4IO_PERF)
|
||||
|
||||
@@ -43,12 +43,12 @@
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
#include <systemlib/ppm_decode.h>
|
||||
#include <rc/st24.h>
|
||||
#include <rc/sumd.h>
|
||||
#include <rc/sbus.h>
|
||||
#include <rc/dsm.h>
|
||||
#include <uORB/topics/input_rc.h>
|
||||
|
||||
#if defined(PX4IO_PERF)
|
||||
# include <perf/perf_counter.h>
|
||||
@@ -56,9 +56,6 @@
|
||||
|
||||
#include "px4io.h"
|
||||
|
||||
#define RC_CHANNEL_HIGH_THRESH 5000 /* 75% threshold */
|
||||
#define RC_CHANNEL_LOW_THRESH -8000 /* 10% threshold */
|
||||
|
||||
static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len);
|
||||
static bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated, bool *sumd_updated);
|
||||
|
||||
@@ -71,13 +68,11 @@ static perf_counter_t c_gather_ppm;
|
||||
static int _dsm_fd = -1;
|
||||
int _sbus_fd = -1;
|
||||
|
||||
static uint16_t rc_value_override = 0;
|
||||
|
||||
#ifdef ADC_RSSI
|
||||
static unsigned _rssi_adc_counts = 0;
|
||||
#endif
|
||||
|
||||
/* receive signal strenght indicator (RSSI). 0 = no connection, 100 (RC_INPUT_RSSI_MAX): perfect connection */
|
||||
/* receive signal strenght indicator (RSSI). 0 = no connection, 100 (input_rc_s::RSSI_MAX): perfect connection */
|
||||
/* Note: this is static because RC-provided telemetry does not occur every tick */
|
||||
static uint16_t _rssi = 0;
|
||||
static unsigned _frame_drops = 0;
|
||||
@@ -136,7 +131,7 @@ bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated, bool
|
||||
if (!(r_status_flags & (PX4IO_P_STATUS_FLAGS_RC_DSM | PX4IO_P_STATUS_FLAGS_RC_SUMD))) {
|
||||
for (unsigned i = 0; i < n_bytes; i++) {
|
||||
/* set updated flag if one complete packet was parsed */
|
||||
st24_rssi = RC_INPUT_RSSI_MAX;
|
||||
st24_rssi = INPUT_RC_RSSI_MAX; // input_rc_s::RSSI_MAX;
|
||||
*st24_updated |= (OK == st24_decode(bytes[i], &st24_rssi, &lost_count,
|
||||
&st24_channel_count, r_raw_rc_values, PX4IO_RC_INPUT_CHANNELS));
|
||||
}
|
||||
@@ -166,7 +161,7 @@ bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated, bool
|
||||
if (!(r_status_flags & (PX4IO_P_STATUS_FLAGS_RC_DSM | PX4IO_P_STATUS_FLAGS_RC_ST24))) {
|
||||
for (unsigned i = 0; i < n_bytes; i++) {
|
||||
/* set updated flag if one complete packet was parsed */
|
||||
sumd_rssi = RC_INPUT_RSSI_MAX;
|
||||
sumd_rssi = INPUT_RC_RSSI_MAX; // input_rc_s::RSSI_MAX;
|
||||
*sumd_updated |= (OK == sumd_decode(bytes[i], &sumd_rssi, &sumd_rx_count,
|
||||
&sumd_channel_count, r_raw_rc_values, PX4IO_RC_INPUT_CHANNELS, &sumd_failsafe_state));
|
||||
}
|
||||
@@ -210,10 +205,6 @@ controls_init(void)
|
||||
unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
|
||||
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_OPTIONS] = 0;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_MIN] = 1000;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_CENTER] = 1500;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_MAX] = 2000;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_DEADZONE] = 30;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_ASSIGNMENT] = i;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_OPTIONS] = PX4IO_P_RC_CONFIG_OPTIONS_ENABLED;
|
||||
}
|
||||
@@ -247,11 +238,11 @@ controls_tick()
|
||||
_rssi_adc_counts = (_rssi_adc_counts * 0.998f) + (counts * 0.002f);
|
||||
/* use 1:1 scaling on 3.3V, 12-Bit ADC input */
|
||||
unsigned mV = _rssi_adc_counts * 3300 / 4095;
|
||||
/* scale to 0..100 (RC_INPUT_RSSI_MAX == 100) */
|
||||
_rssi = (mV * RC_INPUT_RSSI_MAX / 3300);
|
||||
/* scale to 0..100 (input_rc_s::RSSI_MAX == 100) */
|
||||
_rssi = (mV * INPUT_RC_RSSI_MAX / 3300);
|
||||
|
||||
if (_rssi > RC_INPUT_RSSI_MAX) {
|
||||
_rssi = RC_INPUT_RSSI_MAX;
|
||||
if (_rssi > INPUT_RC_RSSI_MAX) {
|
||||
_rssi = INPUT_RC_RSSI_MAX;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -277,11 +268,11 @@ controls_tick()
|
||||
if (sbus_updated) {
|
||||
atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_SBUS);
|
||||
|
||||
unsigned sbus_rssi = RC_INPUT_RSSI_MAX;
|
||||
unsigned sbus_rssi = INPUT_RC_RSSI_MAX; // input_rc_s::RSSI_MAX
|
||||
|
||||
if (sbus_frame_drop) {
|
||||
r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_FRAME_DROP;
|
||||
sbus_rssi = RC_INPUT_RSSI_MAX / 2;
|
||||
sbus_rssi = INPUT_RC_RSSI_MAX / 2;
|
||||
|
||||
} else {
|
||||
r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP);
|
||||
@@ -298,7 +289,6 @@ controls_tick()
|
||||
if (!(r_setup_features & PX4IO_P_SETUP_FEATURES_ADC_RSSI)) {
|
||||
_rssi = sbus_rssi;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
@@ -390,91 +380,27 @@ controls_tick()
|
||||
|
||||
if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) {
|
||||
|
||||
uint16_t raw = r_raw_rc_values[i];
|
||||
|
||||
int16_t scaled;
|
||||
|
||||
/*
|
||||
* 1) Constrain to min/max values, as later processing depends on bounds.
|
||||
*/
|
||||
if (raw < conf[PX4IO_P_RC_CONFIG_MIN]) {
|
||||
raw = conf[PX4IO_P_RC_CONFIG_MIN];
|
||||
}
|
||||
|
||||
if (raw > conf[PX4IO_P_RC_CONFIG_MAX]) {
|
||||
raw = conf[PX4IO_P_RC_CONFIG_MAX];
|
||||
}
|
||||
|
||||
/*
|
||||
* 2) Scale around the mid point differently for lower and upper range.
|
||||
*
|
||||
* This is necessary as they don't share the same endpoints and slope.
|
||||
*
|
||||
* First normalize to 0..1 range with correct sign (below or above center),
|
||||
* then scale to 20000 range (if center is an actual center, -10000..10000,
|
||||
* if parameters only support half range, scale to 10000 range, e.g. if
|
||||
* center == min 0..10000, if center == max -10000..0).
|
||||
*
|
||||
* As the min and max bounds were enforced in step 1), division by zero
|
||||
* cannot occur, as for the case of center == min or center == max the if
|
||||
* statement is mutually exclusive with the arithmetic NaN case.
|
||||
*
|
||||
* DO NOT REMOVE OR ALTER STEP 1!
|
||||
*/
|
||||
if (raw > (conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
|
||||
scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(
|
||||
conf[PX4IO_P_RC_CONFIG_MAX] - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]));
|
||||
|
||||
} else if (raw < (conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
|
||||
scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(
|
||||
conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE] - conf[PX4IO_P_RC_CONFIG_MIN]));
|
||||
|
||||
} else {
|
||||
/* in the configured dead zone, output zero */
|
||||
scaled = 0;
|
||||
}
|
||||
int16_t scaled = 10000.f * r_raw_rc_values[i];
|
||||
|
||||
/* invert channel if requested */
|
||||
if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) {
|
||||
scaled = -scaled;
|
||||
}
|
||||
|
||||
// TODO: find kill switch
|
||||
|
||||
/* and update the scaled/mapped version */
|
||||
unsigned mapped = conf[PX4IO_P_RC_CONFIG_ASSIGNMENT];
|
||||
|
||||
if (mapped < PX4IO_CONTROL_CHANNELS) {
|
||||
|
||||
/* invert channel if pitch - pulling the lever down means pitching up by convention */
|
||||
if (mapped == 1) {
|
||||
/* roll, pitch, yaw, throttle, override is the standard order */
|
||||
scaled = -scaled;
|
||||
}
|
||||
|
||||
if (mapped == 3 && r_setup_rc_thr_failsafe) {
|
||||
/* throttle failsafe detection */
|
||||
if (((raw < conf[PX4IO_P_RC_CONFIG_MIN]) && (raw < r_setup_rc_thr_failsafe)) ||
|
||||
((raw > conf[PX4IO_P_RC_CONFIG_MAX]) && (raw > r_setup_rc_thr_failsafe))) {
|
||||
r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_FAILSAFE;
|
||||
|
||||
} else {
|
||||
r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
|
||||
}
|
||||
}
|
||||
|
||||
r_rc_values[mapped] = SIGNED_TO_REG(scaled);
|
||||
assigned_channels |= (1 << mapped);
|
||||
|
||||
} else if (mapped == PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH) {
|
||||
if (mapped == PX4IO_P_RC_CONFIG_ASSIGNMENT_KILLSWITCH) {
|
||||
/* pick out override channel, indicated by special mapping */
|
||||
rc_value_override = SIGNED_TO_REG(scaled);
|
||||
//rc_value_override = SIGNED_TO_REG(scaled);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* set un-assigned controls to zero */
|
||||
for (unsigned i = 0; i < PX4IO_CONTROL_CHANNELS; i++) {
|
||||
if (!(assigned_channels & (1 << i))) {
|
||||
r_rc_values[i] = 0;
|
||||
// kill engaged
|
||||
// r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_FAILSAFE;
|
||||
// kill disengaged
|
||||
// r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -489,11 +415,6 @@ controls_tick()
|
||||
} else {
|
||||
r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_MAPPING_OK);
|
||||
}
|
||||
|
||||
/*
|
||||
* Export the valid channel bitmap
|
||||
*/
|
||||
r_rc_valid = assigned_channels;
|
||||
}
|
||||
|
||||
/*
|
||||
@@ -517,85 +438,20 @@ controls_tick()
|
||||
* Handle losing RC input
|
||||
*/
|
||||
|
||||
/* if we are in failsafe, clear the override flag */
|
||||
if (r_raw_rc_flags & PX4IO_P_RAW_RC_FLAGS_FAILSAFE) {
|
||||
atomic_modify_clear(&r_status_flags, PX4IO_P_STATUS_FLAGS_OVERRIDE);
|
||||
}
|
||||
|
||||
/* this kicks in if the receiver is gone, but there is not on failsafe (indicated by separate flag) */
|
||||
if (rc_input_lost) {
|
||||
/* Clear the RC input status flag, clear manual override flag */
|
||||
atomic_modify_clear(&r_status_flags, (
|
||||
PX4IO_P_STATUS_FLAGS_OVERRIDE |
|
||||
PX4IO_P_STATUS_FLAGS_RC_OK));
|
||||
atomic_modify_clear(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_OK);
|
||||
|
||||
/* flag raw RC as lost */
|
||||
r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_RC_OK);
|
||||
|
||||
/* Mark all channels as invalid, as we just lost the RX */
|
||||
r_rc_valid = 0;
|
||||
|
||||
/* Set raw channel count to zero */
|
||||
r_raw_rc_count = 0;
|
||||
|
||||
/* Set the RC_LOST alarm */
|
||||
atomic_modify_or(&r_status_alarms, PX4IO_P_STATUS_ALARMS_RC_LOST);
|
||||
}
|
||||
|
||||
/*
|
||||
* Check for manual override.
|
||||
*
|
||||
* Firstly, manual override must be enabled, RC input available and a mixer loaded.
|
||||
*/
|
||||
if (/* condition 1: Override is always allowed */
|
||||
(r_setup_arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) &&
|
||||
/* condition 2: We have valid RC control inputs from the user */
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
|
||||
/* condition 3: The system didn't go already into failsafe mode with fixed outputs */
|
||||
!(r_raw_rc_flags & PX4IO_P_RAW_RC_FLAGS_FAILSAFE) &&
|
||||
/* condition 4: RC handling wasn't generally disabled */
|
||||
!(r_setup_arming & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) &&
|
||||
/* condition 5: We have a valid mixer to map RC inputs to actuator outputs */
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
|
||||
|
||||
bool override = false;
|
||||
|
||||
/*
|
||||
* Check mapped channel 5 (can be any remote channel,
|
||||
* depends on RC_MAP_OVER parameter);
|
||||
* If the value is 'high' then the pilot has
|
||||
* requested override.
|
||||
*
|
||||
*/
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
|
||||
(REG_TO_SIGNED(rc_value_override) < RC_CHANNEL_LOW_THRESH)) {
|
||||
override = true;
|
||||
}
|
||||
|
||||
/*
|
||||
* If the FMU is dead then enable override if we have a mixer
|
||||
* and we want to immediately override (instead of using the RC channel
|
||||
* as in the case above.
|
||||
*
|
||||
* Also, do not enter manual override if we asked for termination
|
||||
* failsafe and FMU is lost.
|
||||
*/
|
||||
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
|
||||
(r_setup_arming & PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE) &&
|
||||
!(r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE)) {
|
||||
override = true;
|
||||
}
|
||||
|
||||
if (override) {
|
||||
atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_OVERRIDE);
|
||||
|
||||
} else {
|
||||
atomic_modify_clear(&r_status_flags, PX4IO_P_STATUS_FLAGS_OVERRIDE);
|
||||
}
|
||||
|
||||
} else {
|
||||
atomic_modify_clear(&r_status_flags, PX4IO_P_STATUS_FLAGS_OVERRIDE);
|
||||
}
|
||||
}
|
||||
|
||||
static bool
|
||||
|
||||
@@ -51,14 +51,8 @@
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <lib/mixer/MixerGroup.hpp>
|
||||
#include <output_limit/output_limit.h>
|
||||
#include <rc/sbus.h>
|
||||
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
|
||||
#include "mixer.h"
|
||||
|
||||
extern "C" {
|
||||
/* #define DEBUG */
|
||||
#include "px4io.h"
|
||||
@@ -85,40 +79,12 @@ extern int _sbus_fd;
|
||||
enum mixer_source {
|
||||
MIX_NONE,
|
||||
MIX_DISARMED,
|
||||
MIX_FMU,
|
||||
MIX_OVERRIDE,
|
||||
MIX_FAILSAFE,
|
||||
MIX_OVERRIDE_FMU_OK
|
||||
};
|
||||
|
||||
static volatile mixer_source source;
|
||||
|
||||
static int mixer_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &control);
|
||||
static int mixer_mix_threadsafe(float *outputs, volatile uint16_t *limits);
|
||||
|
||||
static MixerGroup mixer_group;
|
||||
|
||||
int mixer_mix_threadsafe(float *outputs, volatile uint16_t *limits)
|
||||
{
|
||||
/* poor mans mutex */
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) == 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
in_mixer = true;
|
||||
int mixcount = mixer_group.mix(&outputs[0], PX4IO_SERVO_COUNT);
|
||||
*limits = mixer_group.get_saturation_status();
|
||||
in_mixer = false;
|
||||
|
||||
return mixcount;
|
||||
}
|
||||
|
||||
void
|
||||
mixer_tick()
|
||||
{
|
||||
/* check if the mixer got modified */
|
||||
mixer_handle_text_create_mixer();
|
||||
|
||||
/* check that we are receiving fresh data from the FMU */
|
||||
irqstate_t irq_flags = enter_critical_section();
|
||||
const hrt_abstime fmu_data_received_time = system_state.fmu_data_received_time;
|
||||
@@ -132,8 +98,7 @@ mixer_tick()
|
||||
isr_debug(1, "AP RX timeout");
|
||||
}
|
||||
|
||||
atomic_modify_clear(&r_status_flags, (PX4IO_P_STATUS_FLAGS_FMU_OK));
|
||||
atomic_modify_or(&r_status_alarms, PX4IO_P_STATUS_ALARMS_FMU_LOST);
|
||||
atomic_modify_clear(&r_status_flags, PX4IO_P_STATUS_FLAGS_FMU_OK);
|
||||
|
||||
} else {
|
||||
atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_FMU_OK);
|
||||
@@ -148,7 +113,7 @@ mixer_tick()
|
||||
}
|
||||
|
||||
/* default to disarmed mixing */
|
||||
source = MIX_DISARMED;
|
||||
mixer_source source = MIX_DISARMED;
|
||||
|
||||
/*
|
||||
* Decide which set of controls we're using.
|
||||
@@ -158,39 +123,9 @@ mixer_tick()
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) &&
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {
|
||||
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) > 0) {
|
||||
/* a channel based override has been
|
||||
* triggered, with FMU active */
|
||||
source = MIX_OVERRIDE_FMU_OK;
|
||||
|
||||
} else {
|
||||
/* don't actually mix anything - copy values from r_page_direct_pwm */
|
||||
source = MIX_NONE;
|
||||
memcpy(r_page_servos, r_page_direct_pwm, sizeof(uint16_t)*PX4IO_SERVO_COUNT);
|
||||
}
|
||||
|
||||
} else {
|
||||
|
||||
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
|
||||
|
||||
/* mix from FMU controls */
|
||||
source = MIX_FMU;
|
||||
}
|
||||
|
||||
else if (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) {
|
||||
|
||||
if (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) {
|
||||
|
||||
/* if allowed, mix from RC inputs directly up to available rc channels */
|
||||
source = MIX_OVERRIDE_FMU_OK;
|
||||
|
||||
} else {
|
||||
/* if allowed, mix from RC inputs directly */
|
||||
source = MIX_OVERRIDE;
|
||||
}
|
||||
}
|
||||
/* don't actually mix anything - copy values from r_page_direct_pwm */
|
||||
source = MIX_NONE;
|
||||
memcpy(r_page_servos, r_page_direct_pwm, sizeof(uint16_t)*PX4IO_SERVO_COUNT);
|
||||
}
|
||||
|
||||
/*
|
||||
@@ -200,30 +135,21 @@ mixer_tick()
|
||||
* FMU or from the mixer.
|
||||
*
|
||||
*/
|
||||
should_arm = (
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) /* IO initialised without error */
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) /* and IO is armed */
|
||||
&& (
|
||||
((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) /* and FMU is armed */
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) /* and there is valid input via or mixer */
|
||||
|| (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) /* or direct PWM is set */
|
||||
)
|
||||
should_arm = ((r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) /* IO initialised without error */
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) /* and IO is armed */
|
||||
&& ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) /* and FMU is armed */
|
||||
|| (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) /* or direct PWM is set */
|
||||
)
|
||||
);
|
||||
|
||||
should_arm_nothrottle = (
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) /* IO initialised without error */
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) /* and IO is armed */
|
||||
&& (((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_PREARMED) /* and FMU is prearmed */
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) /* and there is valid input via or mixer */
|
||||
|| (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) /* or direct PWM is set */
|
||||
)
|
||||
);
|
||||
should_arm_nothrottle = ((r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) /* IO initialised without error */
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) /* and IO is armed */
|
||||
&& ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_PREARMED) /* and FMU is prearmed */
|
||||
|| (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) /* or direct PWM is set */
|
||||
));
|
||||
|
||||
should_always_enable_pwm = (
|
||||
(r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE)
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)
|
||||
);
|
||||
should_always_enable_pwm = ((r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
|
||||
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK));
|
||||
|
||||
/*
|
||||
* Check if FMU is still alive, if not, terminate the flight
|
||||
@@ -252,94 +178,19 @@ mixer_tick()
|
||||
atomic_modify_clear(&r_status_flags, (PX4IO_P_STATUS_FLAGS_FAILSAFE));
|
||||
}
|
||||
|
||||
/*
|
||||
* Set simple mixer trim values. If the OK flag is set the mixer is fully loaded.
|
||||
*/
|
||||
if (update_trims && r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) {
|
||||
update_trims = false;
|
||||
mixer_group.set_trims(r_page_servo_control_trim, PX4IO_SERVO_COUNT);
|
||||
}
|
||||
|
||||
/*
|
||||
* Update air-mode parameter
|
||||
*/
|
||||
mixer_group.set_airmode((Mixer::Airmode)REG_TO_SIGNED(r_setup_airmode));
|
||||
|
||||
|
||||
/*
|
||||
* Run the mixers.
|
||||
*/
|
||||
if (source == MIX_FAILSAFE) {
|
||||
|
||||
/* copy failsafe values to the servo outputs */
|
||||
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
|
||||
r_page_servos[i] = r_page_servo_failsafe[i];
|
||||
|
||||
/* safe actuators for FMU feedback */
|
||||
r_page_actuators[i] = FLOAT_TO_REG((r_page_servos[i] - 1500) / 600.0f);
|
||||
}
|
||||
|
||||
} else if (source == MIX_DISARMED) {
|
||||
|
||||
/* copy disarmed values to the servo outputs */
|
||||
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
|
||||
r_page_servos[i] = r_page_servo_disarmed[i];
|
||||
|
||||
/* safe actuators for FMU feedback */
|
||||
r_page_actuators[i] = FLOAT_TO_REG((r_page_servos[i] - 1500) / 600.0f);
|
||||
}
|
||||
|
||||
} else if (source != MIX_NONE && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)
|
||||
&& !(r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN)) {
|
||||
|
||||
float outputs[PX4IO_SERVO_COUNT];
|
||||
unsigned mixed;
|
||||
|
||||
if (REG_TO_FLOAT(r_setup_slew_max) > FLT_EPSILON) {
|
||||
/* maximum value the outputs of the multirotor mixer are allowed to change in this cycle
|
||||
* factor 2 is needed because actuator outputs are in the range [-1,1]
|
||||
*/
|
||||
float delta_out_max = 2.0f * 1000.0f * dt / (r_page_servo_control_max[0] - r_page_servo_control_min[0]) / REG_TO_FLOAT(
|
||||
r_setup_slew_max);
|
||||
mixer_group.set_max_delta_out_once(delta_out_max);
|
||||
}
|
||||
|
||||
/* set dt to be used in simple mixer for slew rate limiting */
|
||||
mixer_group.set_dt_once(dt);
|
||||
|
||||
/* update parameter for mc thrust model if it updated */
|
||||
if (update_mc_thrust_param) {
|
||||
mixer_group.set_thrust_factor(REG_TO_FLOAT(r_setup_thr_fac));
|
||||
update_mc_thrust_param = false;
|
||||
}
|
||||
|
||||
/* mix */
|
||||
mixed = mixer_mix_threadsafe(&outputs[0], &r_mixer_limits);
|
||||
|
||||
/* the pwm limit call takes care of out of band errors */
|
||||
output_limit_calc(should_arm, should_arm_nothrottle, mixed, r_setup_pwm_reverse, r_page_servo_disarmed,
|
||||
r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
|
||||
|
||||
/* clamp unused outputs to zero */
|
||||
for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++) {
|
||||
r_page_servos[i] = 0;
|
||||
outputs[i] = 0.0f;
|
||||
}
|
||||
|
||||
/* store normalized outputs */
|
||||
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
|
||||
r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
|
||||
}
|
||||
|
||||
|
||||
if (mixed && new_fmu_data) {
|
||||
new_fmu_data = false;
|
||||
|
||||
/* Trigger all timer's channels in Oneshot mode to fire
|
||||
* the oneshots with updated values.
|
||||
*/
|
||||
|
||||
up_pwm_update();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -375,7 +226,6 @@ mixer_tick()
|
||||
}
|
||||
|
||||
/* set S.BUS1 or S.BUS2 outputs */
|
||||
|
||||
if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) {
|
||||
sbus2_output(_sbus_fd, r_page_servos, PX4IO_SERVO_COUNT);
|
||||
|
||||
@@ -383,8 +233,7 @@ mixer_tick()
|
||||
sbus1_output(_sbus_fd, r_page_servos, PX4IO_SERVO_COUNT);
|
||||
}
|
||||
|
||||
} else if (mixer_servos_armed && (should_always_enable_pwm
|
||||
|| (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN))) {
|
||||
} else if (mixer_servos_armed && (should_always_enable_pwm || (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN))) {
|
||||
/* set the disarmed servo outputs. */
|
||||
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) {
|
||||
up_pwm_servo_set(i, r_page_servo_disarmed[i]);
|
||||
@@ -402,287 +251,3 @@ mixer_tick()
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int
|
||||
mixer_callback(uintptr_t handle,
|
||||
uint8_t control_group,
|
||||
uint8_t control_index,
|
||||
float &control)
|
||||
{
|
||||
control = 0.0f;
|
||||
|
||||
if (control_group >= PX4IO_CONTROL_GROUPS) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
switch (source) {
|
||||
case MIX_FMU:
|
||||
if (control_index < PX4IO_CONTROL_CHANNELS && control_group < PX4IO_CONTROL_GROUPS) {
|
||||
if (r_page_controls[CONTROL_PAGE_INDEX(control_group, control_index)] == INT16_MAX) {
|
||||
//catch NAN values encoded as INT16 max for disarmed outputs
|
||||
control = NAN;
|
||||
|
||||
} else {
|
||||
control = REG_TO_FLOAT(r_page_controls[CONTROL_PAGE_INDEX(control_group, control_index)]);
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
return -1;
|
||||
|
||||
case MIX_OVERRIDE:
|
||||
if (r_page_rc_input[PX4IO_P_RC_VALID] & (1 << CONTROL_PAGE_INDEX(control_group, control_index))) {
|
||||
control = REG_TO_FLOAT(r_page_rc_input[PX4IO_P_RC_BASE + control_index]);
|
||||
break;
|
||||
}
|
||||
|
||||
return -1;
|
||||
|
||||
case MIX_OVERRIDE_FMU_OK:
|
||||
|
||||
/* FMU is ok but we are in override mode, use direct rc control for the available rc channels. The remaining channels are still controlled by the fmu */
|
||||
if (r_page_rc_input[PX4IO_P_RC_VALID] & (1 << CONTROL_PAGE_INDEX(control_group, control_index))) {
|
||||
control = REG_TO_FLOAT(r_page_rc_input[PX4IO_P_RC_BASE + control_index]);
|
||||
break;
|
||||
|
||||
} else if (control_index < PX4IO_CONTROL_CHANNELS && control_group < PX4IO_CONTROL_GROUPS) {
|
||||
control = REG_TO_FLOAT(r_page_controls[CONTROL_PAGE_INDEX(control_group, control_index)]);
|
||||
break;
|
||||
}
|
||||
|
||||
return -1;
|
||||
|
||||
case MIX_DISARMED:
|
||||
case MIX_FAILSAFE:
|
||||
case MIX_NONE:
|
||||
control = 0.0f;
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* apply trim offsets for override channels */
|
||||
if (source == MIX_OVERRIDE || source == MIX_OVERRIDE_FMU_OK) {
|
||||
if (control_group == actuator_controls_s::GROUP_INDEX_ATTITUDE &&
|
||||
control_index == actuator_controls_s::INDEX_ROLL) {
|
||||
control *= REG_TO_FLOAT(r_setup_scale_roll);
|
||||
control += REG_TO_FLOAT(r_setup_trim_roll);
|
||||
|
||||
} else if (control_group == actuator_controls_s::GROUP_INDEX_ATTITUDE &&
|
||||
control_index == actuator_controls_s::INDEX_PITCH) {
|
||||
control *= REG_TO_FLOAT(r_setup_scale_pitch);
|
||||
control += REG_TO_FLOAT(r_setup_trim_pitch);
|
||||
|
||||
} else if (control_group == actuator_controls_s::GROUP_INDEX_ATTITUDE &&
|
||||
control_index == actuator_controls_s::INDEX_YAW) {
|
||||
control *= REG_TO_FLOAT(r_setup_scale_yaw);
|
||||
control += REG_TO_FLOAT(r_setup_trim_yaw);
|
||||
}
|
||||
}
|
||||
|
||||
/* limit output */
|
||||
if (control > 1.0f) {
|
||||
control = 1.0f;
|
||||
|
||||
} else if (control < -1.0f) {
|
||||
control = -1.0f;
|
||||
}
|
||||
|
||||
/* motor spinup phase - lock throttle to zero */
|
||||
if ((pwm_limit.state == OUTPUT_LIMIT_STATE_RAMP) || (should_arm_nothrottle && !should_arm)) {
|
||||
if ((control_group == actuator_controls_s::GROUP_INDEX_ATTITUDE ||
|
||||
control_group == actuator_controls_s::GROUP_INDEX_ATTITUDE_ALTERNATE) &&
|
||||
control_index == actuator_controls_s::INDEX_THROTTLE) {
|
||||
/* limit the throttle output to zero during motor spinup,
|
||||
* as the motors cannot follow any demand yet
|
||||
*/
|
||||
control = 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
/* only safety off, but not armed - set throttle as invalid */
|
||||
if (should_arm_nothrottle && !should_arm) {
|
||||
if ((control_group == actuator_controls_s::GROUP_INDEX_ATTITUDE ||
|
||||
control_group == actuator_controls_s::GROUP_INDEX_ATTITUDE_ALTERNATE) &&
|
||||
control_index == actuator_controls_s::INDEX_THROTTLE) {
|
||||
/* mark the throttle as invalid */
|
||||
control = NAN;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* XXX error handling here should be more aggressive; currently it is
|
||||
* possible to get STATUS_FLAGS_MIXER_OK set even though the mixer has
|
||||
* not loaded faithfully.
|
||||
*/
|
||||
|
||||
static char mixer_text[PX4IO_MAX_MIXER_LENGTH]; /* large enough for one mixer */
|
||||
static unsigned mixer_text_length = 0;
|
||||
static bool mixer_update_pending = false;
|
||||
|
||||
int
|
||||
mixer_handle_text_create_mixer()
|
||||
{
|
||||
/* only run on update */
|
||||
if (!mixer_update_pending) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* do not allow a mixer change while safety off and FMU armed */
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
|
||||
(r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* abort if we're in the mixer - it will be tried again in the next iteration */
|
||||
if (in_mixer) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* process the text buffer, adding new mixers as their descriptions can be parsed */
|
||||
unsigned resid = mixer_text_length;
|
||||
mixer_group.load_from_buf(mixer_callback, 0, &mixer_text[0], resid);
|
||||
|
||||
/* if anything was parsed */
|
||||
if (resid != mixer_text_length) {
|
||||
|
||||
isr_debug(2, "used %u", mixer_text_length - resid);
|
||||
|
||||
/* copy any leftover text to the base of the buffer for re-use */
|
||||
if (resid > 0) {
|
||||
memmove(&mixer_text[0], &mixer_text[mixer_text_length - resid], resid);
|
||||
/* enforce null termination */
|
||||
mixer_text[resid] = '\0';
|
||||
}
|
||||
|
||||
mixer_text_length = resid;
|
||||
}
|
||||
|
||||
mixer_update_pending = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
mixer_handle_text(const void *buffer, size_t length)
|
||||
{
|
||||
/* do not allow a mixer change while safety off and FMU armed */
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
|
||||
(r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* disable mixing, will be enabled once load is complete */
|
||||
atomic_modify_clear(&r_status_flags, PX4IO_P_STATUS_FLAGS_MIXER_OK);
|
||||
|
||||
/* set the update flags to dirty so we reload those values after a mixer change */
|
||||
update_trims = true;
|
||||
update_mc_thrust_param = true;
|
||||
|
||||
/* abort if we're in the mixer - the caller is expected to retry */
|
||||
if (in_mixer) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
px4io_mixdata *msg = (px4io_mixdata *)buffer;
|
||||
|
||||
isr_debug(2, "mix txt %u", length);
|
||||
|
||||
if (length < sizeof(px4io_mixdata)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
unsigned text_length = length - sizeof(px4io_mixdata);
|
||||
|
||||
switch (msg->action) {
|
||||
case F2I_MIXER_ACTION_RESET:
|
||||
isr_debug(2, "reset");
|
||||
|
||||
/* THEN actually delete it */
|
||||
mixer_group.reset();
|
||||
mixer_text_length = 0;
|
||||
|
||||
/* FALLTHROUGH */
|
||||
case F2I_MIXER_ACTION_APPEND:
|
||||
isr_debug(2, "append %d", length);
|
||||
|
||||
/* check for overflow - this would be really fatal */
|
||||
if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) {
|
||||
atomic_modify_clear(&r_status_flags, PX4IO_P_STATUS_FLAGS_MIXER_OK);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* check if the last item has been processed - bail out if not */
|
||||
if (mixer_update_pending) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* append mixer text and nul-terminate, guard against overflow */
|
||||
memcpy(&mixer_text[mixer_text_length], msg->text, text_length);
|
||||
mixer_text_length += text_length;
|
||||
mixer_text[mixer_text_length] = '\0';
|
||||
isr_debug(2, "buflen %u", mixer_text_length);
|
||||
|
||||
/* flag the buffer as ready */
|
||||
mixer_update_pending = true;
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void
|
||||
mixer_set_failsafe()
|
||||
{
|
||||
/*
|
||||
* Check if a custom failsafe value has been written,
|
||||
* or if the mixer is not ok and bail out.
|
||||
*/
|
||||
|
||||
if ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ||
|
||||
!(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* set failsafe defaults to the values for all inputs = 0 */
|
||||
float outputs[PX4IO_SERVO_COUNT];
|
||||
unsigned mixed;
|
||||
|
||||
if (REG_TO_FLOAT(r_setup_slew_max) > FLT_EPSILON) {
|
||||
/* maximum value the outputs of the multirotor mixer are allowed to change in this cycle
|
||||
* factor 2 is needed because actuator outputs are in the range [-1,1]
|
||||
*/
|
||||
float delta_out_max = 2.0f * 1000.0f * dt / (r_page_servo_control_max[0] - r_page_servo_control_min[0]) / REG_TO_FLOAT(
|
||||
r_setup_slew_max);
|
||||
mixer_group.set_max_delta_out_once(delta_out_max);
|
||||
}
|
||||
|
||||
/* set dt to be used in simple mixer for slew rate limiting */
|
||||
mixer_group.set_dt_once(dt);
|
||||
|
||||
/* update parameter for mc thrust model if it updated */
|
||||
if (update_mc_thrust_param) {
|
||||
mixer_group.set_thrust_factor(REG_TO_FLOAT(r_setup_thr_fac));
|
||||
update_mc_thrust_param = false;
|
||||
}
|
||||
|
||||
/* mix */
|
||||
mixed = mixer_mix_threadsafe(&outputs[0], &r_mixer_limits);
|
||||
|
||||
/* scale to PWM and update the servo outputs as required */
|
||||
for (unsigned i = 0; i < mixed; i++) {
|
||||
|
||||
/* scale to servo output */
|
||||
r_page_servo_failsafe[i] = (outputs[i] * 600.0f) + 1500;
|
||||
|
||||
}
|
||||
|
||||
/* disable the rest of the outputs */
|
||||
for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++) {
|
||||
r_page_servo_failsafe[i] = 0;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -1,42 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2017-2018 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file mixer.h
|
||||
*
|
||||
* PX4IO mixer definitions
|
||||
*
|
||||
* @author Lorenz Meier <lorenz@px4.io>
|
||||
*/
|
||||
#pragma once
|
||||
#define PX4IO_MAX_MIXER_LENGTH 330
|
||||
@@ -61,7 +61,7 @@
|
||||
* the PX4 system are expressed as signed integer values scaled by 10000,
|
||||
* e.g. control values range from -10000..10000. Use the REG_TO_SIGNED and
|
||||
* SIGNED_TO_REG macros to convert between register representation and
|
||||
* the signed version, and REG_TO_FLOAT/FLOAT_TO_REG to convert to float.
|
||||
* the signed version.
|
||||
*
|
||||
* Note that the implementation of readable pages prefers registers within
|
||||
* readable pages to be densely packed. Page numbers do not need to be
|
||||
@@ -75,76 +75,58 @@
|
||||
#define REG_TO_SIGNED(_reg) ((int16_t)(_reg))
|
||||
#define SIGNED_TO_REG(_signed) ((uint16_t)(_signed))
|
||||
|
||||
#define REG_TO_FLOAT(_reg) ((float)REG_TO_SIGNED(_reg) / 10000.0f)
|
||||
#define FLOAT_TO_REG(_float) SIGNED_TO_REG((int16_t)floorf((_float + 0.00005f) * 10000.0f))
|
||||
|
||||
#define REG_TO_BOOL(_reg) ((bool)(_reg))
|
||||
|
||||
#define PX4IO_PROTOCOL_VERSION 4
|
||||
#define PX4IO_PROTOCOL_VERSION 5
|
||||
|
||||
/* maximum allowable sizes on this protocol version */
|
||||
#define PX4IO_PROTOCOL_MAX_CONTROL_COUNT 8 /**< The protocol does not support more than set here, individual units might support less - see PX4IO_P_CONFIG_CONTROL_COUNT */
|
||||
|
||||
/* static configuration page */
|
||||
#define PX4IO_PAGE_CONFIG 0
|
||||
#define PX4IO_PAGE_CONFIG 0
|
||||
#define PX4IO_P_CONFIG_PROTOCOL_VERSION 0 /* PX4IO_PROTOCOL_VERSION */
|
||||
#define PX4IO_P_CONFIG_HARDWARE_VERSION 1 /* magic numbers TBD */
|
||||
#define PX4IO_P_CONFIG_BOOTLOADER_VERSION 2 /* get this how? */
|
||||
#define PX4IO_P_CONFIG_MAX_TRANSFER 3 /* maximum I2C transfer size */
|
||||
#define PX4IO_P_CONFIG_MAX_TRANSFER 3 /* maximum I2C transfer size */
|
||||
#define PX4IO_P_CONFIG_CONTROL_COUNT 4 /* hardcoded max control count supported */
|
||||
#define PX4IO_P_CONFIG_ACTUATOR_COUNT 5 /* hardcoded max actuator output count */
|
||||
#define PX4IO_P_CONFIG_RC_INPUT_COUNT 6 /* hardcoded max R/C input count supported */
|
||||
#define PX4IO_P_CONFIG_ADC_INPUT_COUNT 7 /* hardcoded max ADC inputs */
|
||||
#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* hardcoded # of relay outputs */
|
||||
#define PX4IO_MAX_TRANSFER_LEN 64
|
||||
#define PX4IO_MAX_TRANSFER_LEN 64
|
||||
|
||||
/* dynamic status page */
|
||||
#define PX4IO_PAGE_STATUS 1
|
||||
#define PX4IO_PAGE_STATUS 1
|
||||
#define PX4IO_P_STATUS_FREEMEM 0
|
||||
#define PX4IO_P_STATUS_CPULOAD 1
|
||||
|
||||
#define PX4IO_P_STATUS_FLAGS 2 /* monitoring flags */
|
||||
#define PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED (1 << 0) /* arm-ok and locally armed */
|
||||
#define PX4IO_P_STATUS_FLAGS_OVERRIDE (1 << 1) /* in manual override */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_OK (1 << 2) /* RC input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_PPM (1 << 3) /* PPM input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_DSM (1 << 4) /* DSM input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_SBUS (1 << 5) /* SBUS input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_FMU_OK (1 << 6) /* controls from FMU are valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RAW_PWM (1 << 7) /* raw PWM from FMU is bypassing the mixer */
|
||||
#define PX4IO_P_STATUS_FLAGS_MIXER_OK (1 << 8) /* mixer is OK */
|
||||
#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 9) /* the arming state between IO and FMU is in sync */
|
||||
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */
|
||||
#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */
|
||||
#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF (1 << 12) /* safety is off */
|
||||
#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED (1 << 13) /* FMU was initialized and OK once */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_ST24 (1 << 14) /* ST24 input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_SUMD (1 << 15) /* SUMD input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_OK (1 << 1) /* RC input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_PPM (1 << 2) /* PPM input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_DSM (1 << 3) /* DSM input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_SBUS (1 << 4) /* SBUS input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_FMU_OK (1 << 5) /* controls from FMU are valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RAW_PWM (1 << 6) /* raw PWM from FMU is bypassing the mixer */
|
||||
#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 7) /* the arming state between IO and FMU is in sync */
|
||||
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 8) /* initialisation of the IO completed without error */
|
||||
#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 9) /* failsafe is active */
|
||||
#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF (1 << 10) /* safety is off */
|
||||
#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED (1 << 11) /* FMU was initialized and OK once */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_ST24 (1 << 12) /* ST24 input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_SUMD (1 << 13) /* SUMD input is valid */
|
||||
|
||||
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
|
||||
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* [1] VBatt is very close to regulator dropout */
|
||||
#define PX4IO_P_STATUS_ALARMS_TEMPERATURE (1 << 1) /* board temperature is high */
|
||||
#define PX4IO_P_STATUS_ALARMS_SERVO_CURRENT (1 << 2) /* [1] servo current limit was exceeded */
|
||||
#define PX4IO_P_STATUS_ALARMS_ACC_CURRENT (1 << 3) /* [1] accessory current limit was exceeded */
|
||||
#define PX4IO_P_STATUS_ALARMS_FMU_LOST (1 << 4) /* timed out waiting for controls from FMU */
|
||||
#define PX4IO_P_STATUS_ALARMS_RC_LOST (1 << 5) /* timed out waiting for RC input */
|
||||
#define PX4IO_P_STATUS_ALARMS_PWM_ERROR (1 << 6) /* PWM configuration or output was bad */
|
||||
#define PX4IO_P_STATUS_ALARMS_VSERVO_FAULT (1 << 7) /* [2] VServo was out of the valid range (2.5 - 5.5 V) */
|
||||
#define PX4IO_P_STATUS_ALARMS_RC_LOST (1 << 0) /* timed out waiting for RC input */
|
||||
#define PX4IO_P_STATUS_ALARMS_PWM_ERROR (1 << 1) /* PWM configuration or output was bad */
|
||||
|
||||
#define PX4IO_P_STATUS_VSERVO 6 /* [2] servo rail voltage in mV */
|
||||
#define PX4IO_P_STATUS_VRSSI 7 /* [2] RSSI voltage */
|
||||
#define PX4IO_P_STATUS_PRSSI 8 /* [2] RSSI PWM value */
|
||||
|
||||
#define PX4IO_P_STATUS_MIXER 9 /* mixer actuator limit flags */
|
||||
|
||||
/* array of post-mix actuator outputs, -10000..10000 */
|
||||
#define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* array of PWM servo output values, microseconds */
|
||||
#define PX4IO_PAGE_SERVOS 3 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
#define PX4IO_PAGE_SERVOS 3 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* array of raw RC input values, microseconds */
|
||||
#define PX4IO_PAGE_RAW_RC_INPUT 4
|
||||
#define PX4IO_PAGE_RAW_RC_INPUT 4
|
||||
#define PX4IO_P_RAW_RC_COUNT 0 /* number of valid channels */
|
||||
#define PX4IO_P_RAW_RC_FLAGS 1 /* RC detail status flags */
|
||||
#define PX4IO_P_RAW_RC_FLAGS_FRAME_DROP (1 << 0) /* single frame drop */
|
||||
@@ -159,47 +141,34 @@
|
||||
#define PX4IO_P_RAW_LOST_FRAME_COUNT 5 /* Number of total dropped frames (wrapping counter) */
|
||||
#define PX4IO_P_RAW_RC_BASE 6 /* CONFIG_RC_INPUT_COUNT channels from here */
|
||||
|
||||
/* array of scaled RC input values, -10000..10000 */
|
||||
#define PX4IO_PAGE_RC_INPUT 5
|
||||
#define PX4IO_P_RC_VALID 0 /* bitmask of valid controls */
|
||||
#define PX4IO_P_RC_BASE 1 /* CONFIG_RC_INPUT_COUNT controls from here */
|
||||
|
||||
/* array of raw ADC values */
|
||||
#define PX4IO_PAGE_RAW_ADC_INPUT 6 /* 0..CONFIG_ADC_INPUT_COUNT-1 */
|
||||
#define PX4IO_PAGE_RAW_ADC_INPUT 6 /* 0..CONFIG_ADC_INPUT_COUNT-1 */
|
||||
|
||||
/* PWM servo information */
|
||||
#define PX4IO_PAGE_PWM_INFO 7
|
||||
#define PX4IO_PAGE_PWM_INFO 7
|
||||
#define PX4IO_RATE_MAP_BASE 0 /* 0..CONFIG_ACTUATOR_COUNT bitmaps of PWM rate groups */
|
||||
|
||||
/* setup page */
|
||||
#define PX4IO_PAGE_SETUP 50
|
||||
#define PX4IO_PAGE_SETUP 50
|
||||
#define PX4IO_P_SETUP_FEATURES 0
|
||||
#define PX4IO_P_SETUP_FEATURES_SBUS1_OUT (1 << 0) /**< enable S.Bus v1 output */
|
||||
#define PX4IO_P_SETUP_FEATURES_SBUS2_OUT (1 << 1) /**< enable S.Bus v2 output */
|
||||
#define PX4IO_P_SETUP_FEATURES_PWM_RSSI (1 << 2) /**< enable PWM RSSI parsing */
|
||||
#define PX4IO_P_SETUP_FEATURES_ADC_RSSI (1 << 3) /**< enable ADC RSSI parsing */
|
||||
#define PX4IO_P_SETUP_FEATURES_ADC_RSSI (1 << 2) /**< enable ADC RSSI parsing */
|
||||
|
||||
#define PX4IO_P_SETUP_ARMING 1 /* arming controls */
|
||||
#define PX4IO_P_SETUP_ARMING_IO_ARM_OK (1 << 0) /* OK to arm the IO side */
|
||||
#define PX4IO_P_SETUP_ARMING_FMU_ARMED (1 << 1) /* FMU is already armed */
|
||||
#define PX4IO_P_SETUP_ARMING_FMU_PREARMED (1 << 2) /* FMU is already prearmed */
|
||||
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 3) /* OK to switch to manual override via override RC channel */
|
||||
#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM (1 << 4) /* use custom failsafe values, not 0 values of mixer */
|
||||
#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 5) /* OK to try in-air restart */
|
||||
#define PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE (1 << 6) /* Output of PWM right after startup enabled to help ESCs initialize and prevent them from beeping */
|
||||
#define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED (1 << 7) /* Disable the IO-internal evaluation of the RC */
|
||||
#define PX4IO_P_SETUP_ARMING_LOCKDOWN (1 << 8) /* If set, the system operates normally, but won't actuate any servos */
|
||||
#define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE (1 << 9) /* If set, the system will always output the failsafe values */
|
||||
#define PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE (1 << 10) /* If set, the system will never return from a failsafe, but remain in failsafe once triggered. */
|
||||
#define PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE (1 << 11) /* If set then on FMU failure override is immediate. Othewise it waits for the mode switch to go past the override thrshold */
|
||||
#define PX4IO_P_SETUP_ARMING_IO_ARM_OK (1 << 0) /* OK to arm the IO side */
|
||||
#define PX4IO_P_SETUP_ARMING_FMU_ARMED (1 << 1) /* FMU is already armed */
|
||||
#define PX4IO_P_SETUP_ARMING_FMU_PREARMED (1 << 2) /* FMU is already prearmed */
|
||||
#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM (1 << 3) /* use custom failsafe values, not 0 values of mixer */
|
||||
#define PX4IO_P_SETUP_ARMING_LOCKDOWN (1 << 4) /* If set, the system operates normally, but won't actuate any servos */
|
||||
#define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE (1 << 5) /* If set, the system will always output the failsafe values */
|
||||
#define PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE (1 << 6) /* If set, the system will never return from a failsafe, but remain in failsafe once triggered. */
|
||||
|
||||
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
|
||||
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */
|
||||
#define PX4IO_P_SETUP_PWM_ALTRATE 4 /* 'high' PWM frame output rate in Hz */
|
||||
#define PX4IO_P_SETUP_RELAYS_PAD 5
|
||||
|
||||
#define PX4IO_P_SETUP_VSERVO_SCALE 6 /* hardware rev [2] servo voltage correction factor (float) */
|
||||
#define PX4IO_P_SETUP_DSM 7 /* DSM bind state */
|
||||
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
|
||||
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */
|
||||
#define PX4IO_P_SETUP_PWM_ALTRATE 4 /* 'high' PWM frame output rate in Hz */
|
||||
#define PX4IO_P_SETUP_VSERVO_SCALE 5 /* hardware rev [2] servo voltage correction factor (float) */
|
||||
#define PX4IO_P_SETUP_DSM 6 /* DSM bind state */
|
||||
enum { /* DSM bind states */
|
||||
dsm_bind_power_down = 0,
|
||||
dsm_bind_power_up,
|
||||
@@ -218,63 +187,25 @@ enum { /* DSM bind states */
|
||||
#define PX4IO_P_SETUP_FORCE_SAFETY_OFF 12 /* force safety switch into
|
||||
'armed' (PWM enabled) state - this is a non-data write and
|
||||
hence index 12 can safely be used. */
|
||||
#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 /**< the throttle failsafe pulse length in microseconds */
|
||||
|
||||
#define PX4IO_P_SETUP_FORCE_SAFETY_ON 14 /* force safety switch into 'disarmed' (PWM disabled state) */
|
||||
#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
|
||||
|
||||
#define PX4IO_P_SETUP_PWM_REVERSE 15 /**< Bitmask to reverse PWM channels 1-8 */
|
||||
#define PX4IO_P_SETUP_TRIM_ROLL 16 /**< Roll trim, in actuator units */
|
||||
#define PX4IO_P_SETUP_TRIM_PITCH 17 /**< Pitch trim, in actuator units */
|
||||
#define PX4IO_P_SETUP_TRIM_YAW 18 /**< Yaw trim, in actuator units */
|
||||
#define PX4IO_P_SETUP_SCALE_ROLL 19 /**< Roll scale, in actuator units */
|
||||
#define PX4IO_P_SETUP_SCALE_PITCH 20 /**< Pitch scale, in actuator units */
|
||||
#define PX4IO_P_SETUP_SCALE_YAW 21 /**< Yaw scale, in actuator units */
|
||||
|
||||
#define PX4IO_P_SETUP_SBUS_RATE 22 /**< frame rate of SBUS1 output in Hz */
|
||||
|
||||
#define PX4IO_P_SETUP_MOTOR_SLEW_MAX 24 /**< max motor slew rate */
|
||||
|
||||
#define PX4IO_P_SETUP_THR_MDL_FAC 25 /**< factor for modelling motor control signal output to static thrust relationship */
|
||||
|
||||
#define PX4IO_P_SETUP_THERMAL 26 /**< thermal management */
|
||||
|
||||
#define PX4IO_P_SETUP_AIRMODE 27 /**< air-mode */
|
||||
|
||||
#define PX4IO_P_SETUP_ENABLE_FLIGHTTERMINATION 28 /**< flight termination; false if the circuit breaker (CBRK_FLIGHTTERM) is set */
|
||||
#define PX4IO_P_SETUP_SBUS_RATE 16 /**< frame rate of SBUS1 output in Hz */
|
||||
#define PX4IO_P_SETUP_THERMAL 17 /**< thermal management */
|
||||
#define PX4IO_P_SETUP_ENABLE_FLIGHTTERMINATION 18 /**< flight termination; false if the circuit breaker (CBRK_FLIGHTTERM) is set */
|
||||
|
||||
#define PX4IO_THERMAL_IGNORE UINT16_MAX
|
||||
#define PX4IO_THERMAL_OFF 0
|
||||
#define PX4IO_THERMAL_FULL 10000
|
||||
|
||||
/* autopilot control values, -10000..10000 */
|
||||
#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
|
||||
#define PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
|
||||
#define PX4IO_P_CONTROLS_GROUP_1 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
|
||||
#define PX4IO_P_CONTROLS_GROUP_2 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
|
||||
#define PX4IO_P_CONTROLS_GROUP_3 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 3) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
|
||||
|
||||
#define PX4IO_P_CONTROLS_GROUP_VALID 64
|
||||
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP0 (1 << 0) /**< group 0 is valid / received */
|
||||
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP1 (1 << 1) /**< group 1 is valid / received */
|
||||
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP2 (1 << 2) /**< group 2 is valid / received */
|
||||
#define PX4IO_P_CONTROLS_GROUP_VALID_GROUP3 (1 << 3) /**< group 3 is valid / received */
|
||||
|
||||
/* raw text load to the mixer parser - ignores offset */
|
||||
#define PX4IO_PAGE_MIXERLOAD 52
|
||||
|
||||
/* R/C channel config */
|
||||
#define PX4IO_PAGE_RC_CONFIG 53 /**< R/C input configuration */
|
||||
#define PX4IO_P_RC_CONFIG_MIN 0 /**< lowest input value */
|
||||
#define PX4IO_P_RC_CONFIG_CENTER 1 /**< center input value */
|
||||
#define PX4IO_P_RC_CONFIG_MAX 2 /**< highest input value */
|
||||
#define PX4IO_P_RC_CONFIG_DEADZONE 3 /**< band around center that is ignored */
|
||||
#define PX4IO_P_RC_CONFIG_ASSIGNMENT 4 /**< mapped input value */
|
||||
#define PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH 100 /**< magic value for mode switch */
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS 5 /**< channel options bitmask */
|
||||
#define PX4IO_P_RC_CONFIG_ASSIGNMENT 0 /**< mapped input value */
|
||||
#define PX4IO_P_RC_CONFIG_ASSIGNMENT_KILLSWITCH 100 /**< magic value for kill switch */
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS 1 /**< channel options bitmask */
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED (1 << 0)
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE (1 << 1)
|
||||
#define PX4IO_P_RC_CONFIG_STRIDE 6 /**< spacing between channel config data */
|
||||
#define PX4IO_P_RC_CONFIG_STRIDE 2 /**< spacing between channel config data */
|
||||
|
||||
/* PWM output - overrides mixer */
|
||||
#define PX4IO_PAGE_DIRECT_PWM 54 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
@@ -282,49 +213,16 @@ enum { /* DSM bind states */
|
||||
/* PWM failsafe values - zero disables the output */
|
||||
#define PX4IO_PAGE_FAILSAFE_PWM 55 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* PWM failsafe values - zero disables the output */
|
||||
#define PX4IO_PAGE_SENSORS 56 /**< Sensors connected to PX4IO */
|
||||
#define PX4IO_P_SENSORS_ALTITUDE 0 /**< Altitude of an external sensor (HoTT or S.BUS2) */
|
||||
|
||||
/* Debug and test page - not used in normal operation */
|
||||
#define PX4IO_PAGE_TEST 127
|
||||
#define PX4IO_P_TEST_LED 0 /**< set the amber LED on/off */
|
||||
|
||||
/* PWM minimum values for certain ESCs */
|
||||
#define PX4IO_PAGE_CONTROL_MIN_PWM 106 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* PWM maximum values for certain ESCs */
|
||||
#define PX4IO_PAGE_CONTROL_MAX_PWM 107 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* PWM mtrim values for central position */
|
||||
#define PX4IO_PAGE_CONTROL_TRIM_PWM 108 /**< 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* PWM disarmed values that are active, even when SAFETY_SAFE */
|
||||
#define PX4IO_PAGE_DISARMED_PWM 109 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/**
|
||||
* As-needed mixer data upload.
|
||||
*
|
||||
* This message adds text to the mixer text buffer; the text
|
||||
* buffer is drained as the definitions are consumed.
|
||||
*/
|
||||
#pragma pack(push, 1)
|
||||
struct px4io_mixdata {
|
||||
uint16_t f2i_mixer_magic;
|
||||
#define F2I_MIXER_MAGIC 0x6d74
|
||||
|
||||
uint8_t action;
|
||||
#define F2I_MIXER_ACTION_RESET 0
|
||||
#define F2I_MIXER_ACTION_APPEND 1
|
||||
|
||||
char text[0]; /* actual text size may vary */
|
||||
};
|
||||
#pragma pack(pop)
|
||||
#define PX4IO_PAGE_DISARMED_PWM 109 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/**
|
||||
* Serial protocol encapsulation.
|
||||
*/
|
||||
|
||||
#define PKT_MAX_REGS 32 // by agreement w/FMU
|
||||
|
||||
#pragma pack(push, 1)
|
||||
|
||||
@@ -58,8 +58,6 @@
|
||||
# include <lib/perf/perf_counter.h>
|
||||
#endif
|
||||
|
||||
#include <output_limit/output_limit.h>
|
||||
|
||||
#include <stm32_uart.h>
|
||||
|
||||
#define DEBUG
|
||||
@@ -71,10 +69,6 @@ struct sys_state_s system_state;
|
||||
|
||||
static struct hrt_call serial_dma_call;
|
||||
|
||||
output_limit_t pwm_limit;
|
||||
|
||||
float dt;
|
||||
|
||||
/*
|
||||
* a set of debug buffers to allow us to send debug information from ISRs
|
||||
*/
|
||||
@@ -312,11 +306,6 @@ user_start(int argc, char *argv[])
|
||||
LED_RING(false);
|
||||
#endif
|
||||
|
||||
/* turn on servo power (if supported) */
|
||||
#ifdef POWER_SERVO
|
||||
POWER_SERVO(true);
|
||||
#endif
|
||||
|
||||
/* turn off S.Bus out (if supported) */
|
||||
#ifdef ENABLE_SBUS_OUT
|
||||
ENABLE_SBUS_OUT(false);
|
||||
@@ -349,44 +338,6 @@ user_start(int argc, char *argv[])
|
||||
r_page_status[PX4IO_P_STATUS_FREEMEM] = minfo.mxordblk;
|
||||
syslog(LOG_INFO, "MEM: free %u, largest %u\n", minfo.mxordblk, minfo.fordblks);
|
||||
|
||||
/* initialize PWM limit lib */
|
||||
output_limit_init(&pwm_limit);
|
||||
|
||||
/*
|
||||
* P O L I C E L I G H T S
|
||||
*
|
||||
* Not enough memory, lock down.
|
||||
*
|
||||
* We might need to allocate mixers later, and this will
|
||||
* ensure that a developer doing a change will notice
|
||||
* that he just burned the remaining RAM with static
|
||||
* allocations. We don't want him to be able to
|
||||
* get past that point. This needs to be clearly
|
||||
* documented in the dev guide.
|
||||
*
|
||||
*/
|
||||
if (minfo.mxordblk < 550) {
|
||||
|
||||
syslog(LOG_ERR, "ERR: not enough MEM");
|
||||
bool phase = false;
|
||||
|
||||
while (true) {
|
||||
|
||||
if (phase) {
|
||||
LED_AMBER(true);
|
||||
LED_BLUE(false);
|
||||
|
||||
} else {
|
||||
LED_AMBER(false);
|
||||
LED_BLUE(true);
|
||||
}
|
||||
|
||||
up_udelay(250000);
|
||||
|
||||
phase = !phase;
|
||||
}
|
||||
}
|
||||
|
||||
/* Start the failsafe led init */
|
||||
failsafe_led_init();
|
||||
|
||||
@@ -396,19 +347,8 @@ user_start(int argc, char *argv[])
|
||||
|
||||
uint64_t last_debug_time = 0;
|
||||
uint64_t last_heartbeat_time = 0;
|
||||
uint64_t last_loop_time = 0;
|
||||
|
||||
for (;;) {
|
||||
dt = (hrt_absolute_time() - last_loop_time) / 1000000.0f;
|
||||
last_loop_time = hrt_absolute_time();
|
||||
|
||||
if (dt < 0.0001f) {
|
||||
dt = 0.0001f;
|
||||
|
||||
} else if (dt > 0.02f) {
|
||||
dt = 0.02f;
|
||||
}
|
||||
|
||||
#if defined(PX4IO_PERF)
|
||||
/* track the rate at which the loop is running */
|
||||
perf_count(loop_perf);
|
||||
@@ -446,10 +386,6 @@ user_start(int argc, char *argv[])
|
||||
*/
|
||||
uint32_t heartbeat_period_us = 250 * 1000UL;
|
||||
|
||||
if (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) {
|
||||
heartbeat_period_us /= 4;
|
||||
}
|
||||
|
||||
if ((hrt_absolute_time() - last_heartbeat_time) > heartbeat_period_us) {
|
||||
last_heartbeat_time = hrt_absolute_time();
|
||||
heartbeat_blink();
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user