forked from Archive/PX4-Autopilot
px4/fmu-v5x: remove unused base_phy_DP83848C build variant
This commit is contained in:
parent
d1aec01b86
commit
87ec8839c4
|
@ -97,7 +97,6 @@ pipeline {
|
||||||
"px4_fmu-v5_stackcheck",
|
"px4_fmu-v5_stackcheck",
|
||||||
"px4_fmu-v5_uavcanv0periph",
|
"px4_fmu-v5_uavcanv0periph",
|
||||||
"px4_fmu-v5_uavcanv1",
|
"px4_fmu-v5_uavcanv1",
|
||||||
"px4_fmu-v5x_base_phy_DP83848C",
|
|
||||||
"px4_fmu-v5x_default",
|
"px4_fmu-v5x_default",
|
||||||
"px4_fmu-v6u_default",
|
"px4_fmu-v6u_default",
|
||||||
"px4_fmu-v6x_default",
|
"px4_fmu-v6x_default",
|
||||||
|
|
|
@ -1,289 +0,0 @@
|
||||||
#
|
|
||||||
# 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_MKFATFS 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="../../../../boards/px4/fmu-v5x/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_ARM_MPU_EARLY_RESET=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=0x0033
|
|
||||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v5X.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_SYMBOLS=y
|
|
||||||
CONFIG_DEFAULT_SMALL=y
|
|
||||||
CONFIG_DEV_FIFO_SIZE=0
|
|
||||||
CONFIG_DEV_GPIO=y
|
|
||||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
|
||||||
CONFIG_DEV_PIPE_SIZE=70
|
|
||||||
CONFIG_ETH0_PHY_DP83848C=y
|
|
||||||
CONFIG_FAT_DMAMEMORY=y
|
|
||||||
CONFIG_FAT_LCNAMES=y
|
|
||||||
CONFIG_FAT_LFN=y
|
|
||||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
|
||||||
CONFIG_FDCLONE_STDIO=y
|
|
||||||
CONFIG_FSUTILS_IPCFG=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_MAX_TASKS=64
|
|
||||||
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_IPCFG_BINARY=y
|
|
||||||
CONFIG_IPCFG_CHARDEV=y
|
|
||||||
CONFIG_IPCFG_PATH="/fs/mtd_net"
|
|
||||||
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=3
|
|
||||||
CONFIG_MTD=y
|
|
||||||
CONFIG_MTD_BYTE_WRITE=y
|
|
||||||
CONFIG_MTD_PARTITION=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_DHCPC=y
|
|
||||||
CONFIG_NETINIT_DNS=y
|
|
||||||
CONFIG_NETINIT_DNSIPADDR=0XC0A800FE
|
|
||||||
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
|
|
||||||
CONFIG_NETINIT_MONITOR=y
|
|
||||||
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_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_NET_UDP_WRITE_BUFFERS=y
|
|
||||||
CONFIG_NSH_ARCHINIT=y
|
|
||||||
CONFIG_NSH_ARGCAT=y
|
|
||||||
CONFIG_NSH_BUILTIN_APPS=y
|
|
||||||
CONFIG_NSH_CMDPARMS=y
|
|
||||||
CONFIG_NSH_CROMFSETC=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_OTG_ID_GPIO_DISABLE=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_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_STM32F7_ADC1=y
|
|
||||||
CONFIG_STM32F7_ADC3=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_ETHMAC=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_PHYADDR=0
|
|
||||||
CONFIG_STM32F7_PHYSR=31
|
|
||||||
CONFIG_STM32F7_PHYSR_100MBPS=0x8
|
|
||||||
CONFIG_STM32F7_PHYSR_FULLDUPLEX=0x10
|
|
||||||
CONFIG_STM32F7_PHYSR_MODE=0x10
|
|
||||||
CONFIG_STM32F7_PHYSR_SPEED=0x8
|
|
||||||
CONFIG_STM32F7_PHY_POLLING=y
|
|
||||||
CONFIG_STM32F7_PROGMEM=y
|
|
||||||
CONFIG_STM32F7_PWR=y
|
|
||||||
CONFIG_STM32F7_RTC=y
|
|
||||||
CONFIG_STM32F7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y
|
|
||||||
CONFIG_STM32F7_RTC_MAGIC_REG=1
|
|
||||||
CONFIG_STM32F7_SAVE_CRASHDUMP=y
|
|
||||||
CONFIG_STM32F7_SDMMC2=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_SPI2_DMA=y
|
|
||||||
CONFIG_STM32F7_SPI2_DMA_BUFFER=4096
|
|
||||||
CONFIG_STM32F7_SPI3=y
|
|
||||||
CONFIG_STM32F7_SPI3_DMA=y
|
|
||||||
CONFIG_STM32F7_SPI3_DMA_BUFFER=1024
|
|
||||||
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_TIM3=y
|
|
||||||
CONFIG_STM32F7_TIM9=y
|
|
||||||
CONFIG_STM32F7_UART4=y
|
|
||||||
CONFIG_STM32F7_UART5=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_DHCPC_RENEW=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_UART5_RXBUFSIZE=600
|
|
||||||
CONFIG_UART5_RXDMA=y
|
|
||||||
CONFIG_UART5_TXBUFSIZE=3000
|
|
||||||
CONFIG_UART5_TXDMA=y
|
|
||||||
CONFIG_UART7_BAUD=57600
|
|
||||||
CONFIG_UART7_IFLOWCONTROL=y
|
|
||||||
CONFIG_UART7_OFLOWCONTROL=y
|
|
||||||
CONFIG_UART7_RXBUFSIZE=600
|
|
||||||
CONFIG_UART7_RXDMA=y
|
|
||||||
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_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"
|
|
Loading…
Reference in New Issue