From ac13fb77a950ea6f96ac31f94548f7579035a347 Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Tue, 18 Jun 2024 11:55:22 +0000 Subject: [PATCH] boards: update all NuttX defconfigs --- boards/ark/pi6x/nuttx-config/nsh/defconfig | 4 -- .../nuttx-config/bootloader/defconfig | 8 +-- .../hkust/nxt-dual/nuttx-config/nsh/defconfig | 69 +++++++------------ .../nxt-v1/nuttx-config/bootloader/defconfig | 2 - .../hkust/nxt-v1/nuttx-config/nsh/defconfig | 53 +++++--------- .../h743/nuttx-config/bootloader/defconfig | 4 -- .../nuttx-config/nsh/defconfig | 6 +- .../fmu-v5/nuttx-config/stackcheck/defconfig | 2 - src/modules/zenoh/Kconfig.topics | 10 +++ 9 files changed, 59 insertions(+), 99 deletions(-) diff --git a/boards/ark/pi6x/nuttx-config/nsh/defconfig b/boards/ark/pi6x/nuttx-config/nsh/defconfig index 947fee32b1..0e944e53c9 100644 --- a/boards/ark/pi6x/nuttx-config/nsh/defconfig +++ b/boards/ark/pi6x/nuttx-config/nsh/defconfig @@ -14,7 +14,6 @@ # 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_CAT is not set # CONFIG_NSH_DISABLE_CD is not set # CONFIG_NSH_DISABLE_CP is not set @@ -37,7 +36,6 @@ # CONFIG_NSH_DISABLE_MKFATFS is not set # CONFIG_NSH_DISABLE_MOUNT is not set # CONFIG_NSH_DISABLE_MV is not set -# CONFIG_NSH_DISABLE_NSLOOKUP is not set # CONFIG_NSH_DISABLE_PS is not set # CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set # CONFIG_NSH_DISABLE_PWD is not set @@ -117,8 +115,6 @@ CONFIG_I2C_RESET=y CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_INIT_ENTRYPOINT="nsh_main" CONFIG_INIT_STACKSIZE=3194 -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_THROTTLE=0 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_MAX_EXITFUNS=1 diff --git a/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig b/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig index 42a2a2bcf1..ea894db106 100644 --- a/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig +++ b/boards/hkust/nxt-dual/nuttx-config/bootloader/defconfig @@ -29,14 +29,12 @@ CONFIG_BOARD_INITTHREAD_PRIORITY=254 CONFIG_BOARD_LATE_INITIALIZE=y CONFIG_BOARD_LOOPSPERMSEC=95150 CONFIG_BOARD_RESET_ON_ASSERT=2 -CONFIG_C99_BOOL8=y CONFIG_CDCACM=y CONFIG_CDCACM_IFLOWCONTROL=y CONFIG_CDCACM_PRODUCTID=0x004b CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4" CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 -#TODO:ally for VENDOR ID in the future CONFIG_CDCACM_VENDORID=0x3162 CONFIG_CDCACM_VENDORSTR="Matek" CONFIG_DEBUG_FULLOPT=y @@ -77,15 +75,15 @@ CONFIG_STM32H7_OTGFS=y CONFIG_STM32H7_PROGMEM=y CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y CONFIG_STM32H7_TIM1=y -CONFIG_STM32H7_USART6=y #debug port, can be modified to UART8 -CONFIG_USART6_RXBUFSIZE=600 -CONFIG_USART6_TXBUFSIZE=300 +CONFIG_STM32H7_USART6=y CONFIG_SYSTEMTICK_HOOK=y CONFIG_SYSTEM_CDCACM=y CONFIG_TASK_NAME_SIZE=24 CONFIG_TTY_SIGINT=y CONFIG_TTY_SIGINT_CHAR=0x03 CONFIG_TTY_SIGTSTP=y +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=300 CONFIG_USBDEV=y CONFIG_USBDEV_BUSPOWERED=y CONFIG_USBDEV_MAXPOWER=500 diff --git a/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig b/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig index 8dc5c7cf57..e1e35f96de 100644 --- a/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig +++ b/boards/hkust/nxt-dual/nuttx-config/nsh/defconfig @@ -73,7 +73,6 @@ 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_IFLOWCONTROL=y CONFIG_CDCACM_PRODUCTID=0x0036 @@ -82,12 +81,10 @@ CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 CONFIG_CDCACM_VENDORID=0x1B8C CONFIG_CDCACM_VENDORSTR="Matek" -CONFIG_CLOCK_MONOTONIC=y CONFIG_DEBUG_FULLOPT=y CONFIG_DEBUG_HARDFAULT_ALERT=y CONFIG_DEBUG_MEMFAULT=y CONFIG_DEBUG_SYMBOLS=y -CONFIG_DEBUG_TCBINFO=n CONFIG_DEFAULT_SMALL=y CONFIG_DEV_FIFO_SIZE=0 CONFIG_DEV_PIPE_MAXSIZE=1024 @@ -114,10 +111,10 @@ CONFIG_HAVE_CXXINITIALIZE=y CONFIG_I2C=y CONFIG_I2C_RESET=y CONFIG_IDLETHREAD_STACKSIZE=750 -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_NCHAINS=24 CONFIG_INIT_ENTRYPOINT="nsh_main" CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_MAX_EXITFUNS=1 @@ -129,7 +126,6 @@ CONFIG_MMCSD_SDIO=y CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y CONFIG_MM_IOB=y CONFIG_MM_REGIONS=4 -# Avaible in Dual Version TODO: MTD IO error CONFIG_MTD=y CONFIG_MTD_BYTE_WRITE=y CONFIG_MTD_PARTITION=y @@ -164,7 +160,6 @@ CONFIG_RAW_BINARY=y CONFIG_READLINE_CMD_HISTORY=y CONFIG_READLINE_TABCOMPLETION=y CONFIG_RTC_DATETIME=y -CONFIG_SCHED_ATEXIT=y CONFIG_SCHED_HPWORK=y CONFIG_SCHED_HPWORKPRIORITY=249 CONFIG_SCHED_HPWORKSTACKSIZE=1280 @@ -175,7 +170,6 @@ CONFIG_SCHED_LPWORK=y CONFIG_SCHED_LPWORKPRIORITY=50 CONFIG_SCHED_LPWORKSTACKSIZE=1632 CONFIG_SCHED_WAITPID=y -CONFIG_SDCLONE_DISABLE=y CONFIG_SDMMC1_SDIO_PULLUP=y CONFIG_SEM_PREALLOCHOLDERS=32 CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y @@ -191,7 +185,7 @@ CONFIG_START_MONTH=11 CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STM32H7_ADC1=y CONFIG_STM32H7_ADC2=y -CONFIG_STM32H7_ADC3=y #should always enable otherwsie got ADC timeout error this is for tempreature compenstae +CONFIG_STM32H7_ADC3=y CONFIG_STM32H7_BBSRAM=y CONFIG_STM32H7_BBSRAM_FILES=5 CONFIG_STM32H7_BDMA=y @@ -212,40 +206,28 @@ CONFIG_STM32H7_RTC_HSECLOCK=y CONFIG_STM32H7_RTC_MAGIC_REG=1 CONFIG_STM32H7_SAVE_CRASHDUMP=y CONFIG_STM32H7_SDMMC1=y -CONFIG_STM32H7_SDMMC1_DMA=y -CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024 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_SPI4=y -# CONFIG_STM32H7_SPI4_DMA=y -# CONFIG_STM32H7_SPI4_DMA_BUFFER=1024 -CONFIG_STM32H7_SPI_DMA=y CONFIG_STM32H7_SPI_DMATHRESHOLD=8 CONFIG_STM32H7_TIM1=y CONFIG_STM32H7_TIM2=y CONFIG_STM32H7_TIM3=y CONFIG_STM32H7_TIM4=y -# CONFIG_STM32H7_TIM5=y -# CONFIG_STM32H7_TIM6=y -# CONFIG_STM32H7_TIM7=y CONFIG_STM32H7_TIM8=y -CONFIG_STM32H7_USART1=y #ttyS0 -CONFIG_STM32H7_USART2=y #ttyS1 -CONFIG_STM32H7_USART3=y #ttyS2 -CONFIG_STM32H7_UART4=y #ttyS3 -CONFIG_STM32H7_UART5=y #ttyS4 -CONFIG_STM32H7_USART6=y #ttyS5 NC -CONFIG_STM32H7_UART7=y #ttyS6 -CONFIG_STM32H7_UART8=y #ttyS7 +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 @@ -253,6 +235,20 @@ CONFIG_STM32H7_USART_SWAP=y CONFIG_SYSTEM_CDCACM=y CONFIG_SYSTEM_NSH=y CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=921600 +CONFIG_UART4_RXBUFSIZE=3000 +CONFIG_UART4_RXDMA=y +CONFIG_UART4_TXBUFSIZE=3000 +CONFIG_UART4_TXDMA=y +CONFIG_UART5_BAUD=57600 +CONFIG_UART5_RXBUFSIZE=600 +CONFIG_UART5_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=3000 CONFIG_USART1_BAUD=57600 CONFIG_USART1_RXBUFSIZE=600 CONFIG_USART1_TXBUFSIZE=1500 @@ -262,27 +258,12 @@ CONFIG_USART2_TXBUFSIZE=3000 CONFIG_USART3_BAUD=57600 CONFIG_USART3_RXBUFSIZE=180 CONFIG_USART3_TXBUFSIZE=1500 -CONFIG_UART4_BAUD=921600 -CONFIG_UART4_RXBUFSIZE=3000 -CONFIG_UART4_TXBUFSIZE=3000 -CONFIG_UART4_RXDMA=y -CONFIG_UART4_TXDMA=y -CONFIG_UART5_BAUD=57600 -CONFIG_UART5_RXBUFSIZE=600 -CONFIG_UART5_TXBUFSIZE=1500 CONFIG_USART6_BAUD=57600 CONFIG_USART6_RXBUFSIZE=180 CONFIG_USART6_SERIAL_CONSOLE=y -CONFIG_UART7_BAUD=57600 -CONFIG_UART7_RXBUFSIZE=600 -CONFIG_UART7_TXBUFSIZE=3000 -CONFIG_UART8_BAUD=57600 -CONFIG_UART8_RXBUFSIZE=600 -CONFIG_UART8_TXBUFSIZE=3000 CONFIG_USBDEV=y CONFIG_USBDEV_BUSPOWERED=y CONFIG_USBDEV_MAXPOWER=500 CONFIG_USEC_PER_TICK=1000 -CONFIG_USERMAIN_STACKSIZE=2944 CONFIG_WATCHDOG=y CONFIG_WQUEUE_NOTIFIER=y diff --git a/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig b/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig index e051eadacd..6cf4a40708 100644 --- a/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig +++ b/boards/hkust/nxt-v1/nuttx-config/bootloader/defconfig @@ -29,14 +29,12 @@ CONFIG_BOARD_INITTHREAD_PRIORITY=254 CONFIG_BOARD_LATE_INITIALIZE=y CONFIG_BOARD_LOOPSPERMSEC=95150 CONFIG_BOARD_RESET_ON_ASSERT=2 -CONFIG_C99_BOOL8=y CONFIG_CDCACM=y CONFIG_CDCACM_IFLOWCONTROL=y CONFIG_CDCACM_PRODUCTID=0x004b CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4" CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 -#TODO:ally for VENDOR ID in the future CONFIG_CDCACM_VENDORID=0x3162 CONFIG_CDCACM_VENDORSTR="Matek" CONFIG_DEBUG_FULLOPT=y diff --git a/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig b/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig index 202258c5c6..21c65a81ee 100644 --- a/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig +++ b/boards/hkust/nxt-v1/nuttx-config/nsh/defconfig @@ -73,7 +73,6 @@ 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_IFLOWCONTROL=y CONFIG_CDCACM_PRODUCTID=0x0036 @@ -82,12 +81,10 @@ CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 CONFIG_CDCACM_VENDORID=0x1B8C CONFIG_CDCACM_VENDORSTR="Matek" -CONFIG_CLOCK_MONOTONIC=y CONFIG_DEBUG_FULLOPT=y CONFIG_DEBUG_HARDFAULT_ALERT=y CONFIG_DEBUG_MEMFAULT=y CONFIG_DEBUG_SYMBOLS=y -CONFIG_DEBUG_TCBINFO=n CONFIG_DEFAULT_SMALL=y CONFIG_DEV_FIFO_SIZE=0 CONFIG_DEV_PIPE_MAXSIZE=1024 @@ -114,10 +111,10 @@ CONFIG_HAVE_CXXINITIALIZE=y CONFIG_I2C=y CONFIG_I2C_RESET=y CONFIG_IDLETHREAD_STACKSIZE=750 -CONFIG_IOB_NBUFFERS=24 -CONFIG_IOB_NCHAINS=24 CONFIG_INIT_ENTRYPOINT="nsh_main" CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_MAX_EXITFUNS=1 @@ -129,12 +126,6 @@ CONFIG_MMCSD_SDIO=y CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y CONFIG_MM_IOB=y CONFIG_MM_REGIONS=4 -# Avaible in Dual Version -# 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_NSH_ARCHINIT=y CONFIG_NSH_ARGCAT=y @@ -155,14 +146,12 @@ 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_READLINE_CMD_HISTORY=y CONFIG_READLINE_TABCOMPLETION=y CONFIG_RTC_DATETIME=y -CONFIG_SCHED_ATEXIT=y CONFIG_SCHED_HPWORK=y CONFIG_SCHED_HPWORKPRIORITY=249 CONFIG_SCHED_HPWORKSTACKSIZE=1280 @@ -173,7 +162,6 @@ CONFIG_SCHED_LPWORK=y CONFIG_SCHED_LPWORKPRIORITY=50 CONFIG_SCHED_LPWORKSTACKSIZE=1632 CONFIG_SCHED_WAITPID=y -CONFIG_SDCLONE_DISABLE=y CONFIG_SDMMC1_SDIO_PULLUP=y CONFIG_SEM_PREALLOCHOLDERS=32 CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y @@ -189,7 +177,7 @@ CONFIG_START_MONTH=11 CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STM32H7_ADC1=y CONFIG_STM32H7_ADC2=y -CONFIG_STM32H7_ADC3=y #should always enable otherwsie got ADC timeout error this is for tempreature compenstae +CONFIG_STM32H7_ADC3=y CONFIG_STM32H7_BBSRAM=y CONFIG_STM32H7_BBSRAM_FILES=5 CONFIG_STM32H7_BDMA=y @@ -210,8 +198,6 @@ CONFIG_STM32H7_RTC_HSECLOCK=y CONFIG_STM32H7_RTC_MAGIC_REG=1 CONFIG_STM32H7_SAVE_CRASHDUMP=y CONFIG_STM32H7_SDMMC1=y -CONFIG_STM32H7_SDMMC1_DMA=y -CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024 CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y CONFIG_STM32H7_SPI1=y @@ -223,19 +209,18 @@ CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 CONFIG_STM32H7_SPI3=y CONFIG_STM32H7_SPI3_DMA=y CONFIG_STM32H7_SPI3_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_TIM5=y CONFIG_STM32H7_TIM8=y -CONFIG_STM32H7_USART1=y #ttyS0 -CONFIG_STM32H7_USART2=y #ttyS1 -CONFIG_STM32H7_USART3=y #ttyS2 -CONFIG_STM32H7_UART4=y #ttyS3 -CONFIG_STM32H7_UART5=y #ttyS4 -CONFIG_STM32H7_UART7=y #ttyS5 +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y CONFIG_STM32H7_USART_BREAKS=y CONFIG_STM32H7_USART_INVERT=y CONFIG_STM32H7_USART_SINGLEWIRE=y @@ -243,6 +228,15 @@ CONFIG_STM32H7_USART_SWAP=y CONFIG_SYSTEM_CDCACM=y CONFIG_SYSTEM_NSH=y CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=921600 +CONFIG_UART4_RXBUFSIZE=3000 +CONFIG_UART4_TXBUFSIZE=1200 +CONFIG_UART5_BAUD=57600 +CONFIG_UART5_RXBUFSIZE=600 +CONFIG_UART5_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=3000 CONFIG_USART1_BAUD=57600 CONFIG_USART1_RXBUFSIZE=600 CONFIG_USART1_TXBUFSIZE=1500 @@ -253,20 +247,9 @@ CONFIG_USART3_BAUD=57600 CONFIG_USART3_RXBUFSIZE=180 CONFIG_USART3_SERIAL_CONSOLE=y CONFIG_USART3_TXBUFSIZE=1500 -CONFIG_UART4_BAUD=921600 -CONFIG_UART4_RXBUFSIZE=3000 -CONFIG_UART4_TXBUFSIZE=1200 -CONFIG_UART5_BAUD=57600 -CONFIG_UART5_RXBUFSIZE=600 -CONFIG_UART5_TXBUFSIZE=1500 -CONFIG_UART7_BAUD=57600 -CONFIG_UART7_RXBUFSIZE=600 -CONFIG_UART7_TXBUFSIZE=3000 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 CONFIG_WQUEUE_NOTIFIER=y diff --git a/boards/micoair/h743/nuttx-config/bootloader/defconfig b/boards/micoair/h743/nuttx-config/bootloader/defconfig index 76254f1327..81e907784e 100644 --- a/boards/micoair/h743/nuttx-config/bootloader/defconfig +++ b/boards/micoair/h743/nuttx-config/bootloader/defconfig @@ -29,14 +29,12 @@ CONFIG_BOARD_INITTHREAD_PRIORITY=254 CONFIG_BOARD_LATE_INITIALIZE=y CONFIG_BOARD_LOOPSPERMSEC=95150 CONFIG_BOARD_RESET_ON_ASSERT=2 -CONFIG_C99_BOOL8=y CONFIG_CDCACM=y CONFIG_CDCACM_IFLOWCONTROL=y CONFIG_CDCACM_PRODUCTID=0x004b CONFIG_CDCACM_PRODUCTSTR="MicoAir743" CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_TXBUFSIZE=12000 -#TODO:ally for VENDOR ID in the future CONFIG_CDCACM_VENDORID=0x3162 CONFIG_CDCACM_VENDORSTR="MicoAir" CONFIG_DEBUG_FULLOPT=y @@ -61,7 +59,6 @@ CONFIG_PTHREAD_STACK_MIN=512 CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 CONFIG_RAW_BINARY=y -CONFIG_SERIAL_TERMIOS=y CONFIG_SIG_DEFAULT=y CONFIG_SIG_SIGALRM_ACTION=y CONFIG_SIG_SIGUSR1_ACTION=y @@ -75,7 +72,6 @@ CONFIG_STM32H7_BKPSRAM=y CONFIG_STM32H7_DMA1=y CONFIG_STM32H7_OTGFS=y CONFIG_STM32H7_PROGMEM=y -CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y CONFIG_STM32H7_TIM1=y CONFIG_SYSTEMTICK_HOOK=y CONFIG_SYSTEM_CDCACM=y diff --git a/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig index 7e56401723..1d75bb419d 100644 --- a/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig @@ -219,12 +219,12 @@ CONFIG_STM32H7_TIM2=y CONFIG_STM32H7_TIM3=y CONFIG_STM32H7_TIM4=y CONFIG_STM32H7_TIM8=y -CONFIG_STM32H7_USART1=y -CONFIG_STM32H7_USART2=y -CONFIG_STM32H7_USART3=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_USART_BREAKS=y CONFIG_STM32H7_USART_INVERT=y CONFIG_STM32H7_USART_SINGLEWIRE=y diff --git a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig index 59fc098655..8435ec217b 100644 --- a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig @@ -116,7 +116,6 @@ CONFIG_INIT_STACKSIZE=3194 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_MAX_EXITFUNS=1 -CONFIG_LIBC_STRERROR=n CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y @@ -139,7 +138,6 @@ 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_OTG_ID_GPIO_DISABLE=y CONFIG_PIPES=y diff --git a/src/modules/zenoh/Kconfig.topics b/src/modules/zenoh/Kconfig.topics index 58e5e522cd..e1c2ea4ada 100644 --- a/src/modules/zenoh/Kconfig.topics +++ b/src/modules/zenoh/Kconfig.topics @@ -245,6 +245,10 @@ menu "Zenoh publishers/subscribers" bool "follow_target_status" default n + config ZENOH_PUBSUB_FUEL_TANK_STATUS + bool "fuel_tank_status" + default n + config ZENOH_PUBSUB_GENERATOR_STATUS bool "generator_status" default n @@ -565,6 +569,10 @@ menu "Zenoh publishers/subscribers" bool "register_ext_component_request" default n + config ZENOH_PUBSUB_ROVER_ACKERMANN_GUIDANCE_STATUS + bool "rover_ackermann_guidance_status" + default n + config ZENOH_PUBSUB_RPM bool "rpm" default n @@ -919,6 +927,7 @@ config ZENOH_PUBSUB_ALL_SELECTION select ZENOH_PUBSUB_FOLLOW_TARGET select ZENOH_PUBSUB_FOLLOW_TARGET_ESTIMATOR select ZENOH_PUBSUB_FOLLOW_TARGET_STATUS + select ZENOH_PUBSUB_FUEL_TANK_STATUS select ZENOH_PUBSUB_GENERATOR_STATUS select ZENOH_PUBSUB_GEOFENCE_RESULT select ZENOH_PUBSUB_GEOFENCE_STATUS @@ -999,6 +1008,7 @@ config ZENOH_PUBSUB_ALL_SELECTION select ZENOH_PUBSUB_RC_PARAMETER_MAP select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REPLY select ZENOH_PUBSUB_REGISTER_EXT_COMPONENT_REQUEST + select ZENOH_PUBSUB_ROVER_ACKERMANN_GUIDANCE_STATUS select ZENOH_PUBSUB_RPM select ZENOH_PUBSUB_RTL_STATUS select ZENOH_PUBSUB_RTL_TIME_ESTIMATE