diff --git a/boards/ark/can-flow/nuttx-config/canbootloader/defconfig b/boards/ark/can-flow/nuttx-config/canbootloader/defconfig index 40dffb67e8..6ce4a95b09 100644 --- a/boards/ark/can-flow/nuttx-config/canbootloader/defconfig +++ b/boards/ark/can-flow/nuttx-config/canbootloader/defconfig @@ -36,7 +36,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=0 +CONFIG_FS_PROCFS_MAX_TASKS=0 CONFIG_MM_REGIONS=2 CONFIG_NAME_MAX=0 CONFIG_NUNGET_CHARS=0 diff --git a/boards/ark/can-gps/nuttx-config/canbootloader/defconfig b/boards/ark/can-gps/nuttx-config/canbootloader/defconfig index 40dffb67e8..6ce4a95b09 100644 --- a/boards/ark/can-gps/nuttx-config/canbootloader/defconfig +++ b/boards/ark/can-gps/nuttx-config/canbootloader/defconfig @@ -36,7 +36,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=0 +CONFIG_FS_PROCFS_MAX_TASKS=0 CONFIG_MM_REGIONS=2 CONFIG_NAME_MAX=0 CONFIG_NUNGET_CHARS=0 diff --git a/boards/av/x-v1/nuttx-config/nsh/defconfig b/boards/av/x-v1/nuttx-config/nsh/defconfig index 0d6476c8f3..298b41e4cf 100644 --- a/boards/av/x-v1/nuttx-config/nsh/defconfig +++ b/boards/av/x-v1/nuttx-config/nsh/defconfig @@ -91,7 +91,7 @@ CONFIG_IOB_NBUFFERS=24 CONFIG_IOB_THROTTLE=0 CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/cuav/can-gps-v1/nuttx-config/canbootloader/defconfig b/boards/cuav/can-gps-v1/nuttx-config/canbootloader/defconfig index 73eae9027f..b37c029a83 100644 --- a/boards/cuav/can-gps-v1/nuttx-config/canbootloader/defconfig +++ b/boards/cuav/can-gps-v1/nuttx-config/canbootloader/defconfig @@ -36,7 +36,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=0 +CONFIG_FS_PROCFS_MAX_TASKS=0 CONFIG_MM_REGIONS=2 CONFIG_NAME_MAX=0 CONFIG_NUNGET_CHARS=0 diff --git a/boards/cuav/nora/nuttx-config/bootloader/defconfig b/boards/cuav/nora/nuttx-config/bootloader/defconfig index 5bd005f110..ee976d60ff 100644 --- a/boards/cuav/nora/nuttx-config/bootloader/defconfig +++ b/boards/cuav/nora/nuttx-config/bootloader/defconfig @@ -51,7 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=8 +CONFIG_FS_PROCFS_MAX_TASKS=8 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_PREALLOC_TIMERS=50 diff --git a/boards/cuav/nora/nuttx-config/nsh/defconfig b/boards/cuav/nora/nuttx-config/nsh/defconfig index 66586e039f..e9aba8f45e 100644 --- a/boards/cuav/nora/nuttx-config/nsh/defconfig +++ b/boards/cuav/nora/nuttx-config/nsh/defconfig @@ -82,7 +82,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/cuav/x7pro/nuttx-config/bootloader/defconfig b/boards/cuav/x7pro/nuttx-config/bootloader/defconfig index 433c1a9c3e..643b32ef26 100644 --- a/boards/cuav/x7pro/nuttx-config/bootloader/defconfig +++ b/boards/cuav/x7pro/nuttx-config/bootloader/defconfig @@ -51,7 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=8 +CONFIG_FS_PROCFS_MAX_TASKS=8 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_PREALLOC_TIMERS=50 diff --git a/boards/cuav/x7pro/nuttx-config/nsh/defconfig b/boards/cuav/x7pro/nuttx-config/nsh/defconfig index 0df8cec7cb..f2f51677cc 100644 --- a/boards/cuav/x7pro/nuttx-config/nsh/defconfig +++ b/boards/cuav/x7pro/nuttx-config/nsh/defconfig @@ -82,7 +82,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/cubepilot/cubeorange/nuttx-config/bootloader/defconfig b/boards/cubepilot/cubeorange/nuttx-config/bootloader/defconfig index 97eeaa316d..fa9c9efa4a 100644 --- a/boards/cubepilot/cubeorange/nuttx-config/bootloader/defconfig +++ b/boards/cubepilot/cubeorange/nuttx-config/bootloader/defconfig @@ -51,7 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=8 +CONFIG_FS_PROCFS_MAX_TASKS=8 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_PREALLOC_TIMERS=50 diff --git a/boards/cubepilot/cubeorange/nuttx-config/nsh/defconfig b/boards/cubepilot/cubeorange/nuttx-config/nsh/defconfig index 7a3dca0146..9718b70442 100644 --- a/boards/cubepilot/cubeorange/nuttx-config/nsh/defconfig +++ b/boards/cubepilot/cubeorange/nuttx-config/nsh/defconfig @@ -83,7 +83,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/cubepilot/cubeorange/nuttx-config/test/defconfig b/boards/cubepilot/cubeorange/nuttx-config/test/defconfig index 3aca0a88aa..b1200d34a2 100644 --- a/boards/cubepilot/cubeorange/nuttx-config/test/defconfig +++ b/boards/cubepilot/cubeorange/nuttx-config/test/defconfig @@ -82,7 +82,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/cubepilot/cubeyellow/nuttx-config/nsh/defconfig b/boards/cubepilot/cubeyellow/nuttx-config/nsh/defconfig index c52d4f7b06..d4b0ff9c98 100644 --- a/boards/cubepilot/cubeyellow/nuttx-config/nsh/defconfig +++ b/boards/cubepilot/cubeyellow/nuttx-config/nsh/defconfig @@ -84,7 +84,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/cubepilot/cubeyellow/nuttx-config/test/defconfig b/boards/cubepilot/cubeyellow/nuttx-config/test/defconfig index b3040e9b85..20f1e8d925 100644 --- a/boards/cubepilot/cubeyellow/nuttx-config/test/defconfig +++ b/boards/cubepilot/cubeyellow/nuttx-config/test/defconfig @@ -83,7 +83,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/cubepilot/io-v2/nuttx-config/nsh/defconfig b/boards/cubepilot/io-v2/nuttx-config/nsh/defconfig index 324931beb6..cc8229fca7 100644 --- a/boards/cubepilot/io-v2/nuttx-config/nsh/defconfig +++ b/boards/cubepilot/io-v2/nuttx-config/nsh/defconfig @@ -28,7 +28,7 @@ CONFIG_FDCLONE_STDIO=y CONFIG_HAVE_CXX=y CONFIG_HAVE_CXXINITIALIZE=y CONFIG_IDLETHREAD_STACKSIZE=280 -CONFIG_MAX_TASKS=2 +CONFIG_FS_PROCFS_MAX_TASKS=2 CONFIG_MM_FILL_ALLOCATIONS=y CONFIG_MM_SMALL=y CONFIG_NAME_MAX=12 diff --git a/boards/freefly/can-rtk-gps/nuttx-config/canbootloader/defconfig b/boards/freefly/can-rtk-gps/nuttx-config/canbootloader/defconfig index c4f79b1a24..286ad14f11 100644 --- a/boards/freefly/can-rtk-gps/nuttx-config/canbootloader/defconfig +++ b/boards/freefly/can-rtk-gps/nuttx-config/canbootloader/defconfig @@ -40,7 +40,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=0 +CONFIG_FS_PROCFS_MAX_TASKS=0 CONFIG_MM_REGIONS=2 CONFIG_NAME_MAX=0 CONFIG_NUNGET_CHARS=0 diff --git a/boards/holybro/can-gps-v1/nuttx-config/canbootloader/defconfig b/boards/holybro/can-gps-v1/nuttx-config/canbootloader/defconfig index 40dffb67e8..6ce4a95b09 100644 --- a/boards/holybro/can-gps-v1/nuttx-config/canbootloader/defconfig +++ b/boards/holybro/can-gps-v1/nuttx-config/canbootloader/defconfig @@ -36,7 +36,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=0 +CONFIG_FS_PROCFS_MAX_TASKS=0 CONFIG_MM_REGIONS=2 CONFIG_NAME_MAX=0 CONFIG_NUNGET_CHARS=0 diff --git a/boards/holybro/durandal-v1/nuttx-config/bootloader/defconfig b/boards/holybro/durandal-v1/nuttx-config/bootloader/defconfig index 85a13ed6c7..88aa8309f9 100644 --- a/boards/holybro/durandal-v1/nuttx-config/bootloader/defconfig +++ b/boards/holybro/durandal-v1/nuttx-config/bootloader/defconfig @@ -51,7 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=8 +CONFIG_FS_PROCFS_MAX_TASKS=8 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_PREALLOC_TIMERS=50 diff --git a/boards/holybro/durandal-v1/nuttx-config/nsh/defconfig b/boards/holybro/durandal-v1/nuttx-config/nsh/defconfig index bc2e6fffe2..f66df97dcf 100644 --- a/boards/holybro/durandal-v1/nuttx-config/nsh/defconfig +++ b/boards/holybro/durandal-v1/nuttx-config/nsh/defconfig @@ -83,7 +83,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/holybro/kakutef7/nuttx-config/nsh/defconfig b/boards/holybro/kakutef7/nuttx-config/nsh/defconfig index 3c6c15e3b8..53c349ed16 100644 --- a/boards/holybro/kakutef7/nuttx-config/nsh/defconfig +++ b/boards/holybro/kakutef7/nuttx-config/nsh/defconfig @@ -86,7 +86,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/holybro/pix32v5/nuttx-config/nsh/defconfig b/boards/holybro/pix32v5/nuttx-config/nsh/defconfig index 797e3e5b24..1e657cb8e3 100644 --- a/boards/holybro/pix32v5/nuttx-config/nsh/defconfig +++ b/boards/holybro/pix32v5/nuttx-config/nsh/defconfig @@ -83,7 +83,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/modalai/fc-v1/nuttx-config/nsh/defconfig b/boards/modalai/fc-v1/nuttx-config/nsh/defconfig index 2b8d4ffe8a..84f7caa824 100644 --- a/boards/modalai/fc-v1/nuttx-config/nsh/defconfig +++ b/boards/modalai/fc-v1/nuttx-config/nsh/defconfig @@ -82,7 +82,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/modalai/fc-v2/nuttx-config/bootloader/defconfig b/boards/modalai/fc-v2/nuttx-config/bootloader/defconfig index 800a390632..55c0470a5a 100644 --- a/boards/modalai/fc-v2/nuttx-config/bootloader/defconfig +++ b/boards/modalai/fc-v2/nuttx-config/bootloader/defconfig @@ -51,7 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=8 +CONFIG_FS_PROCFS_MAX_TASKS=8 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_PREALLOC_TIMERS=50 diff --git a/boards/modalai/fc-v2/nuttx-config/nsh/defconfig b/boards/modalai/fc-v2/nuttx-config/nsh/defconfig index 8bb25700f7..2bb72f134d 100644 --- a/boards/modalai/fc-v2/nuttx-config/nsh/defconfig +++ b/boards/modalai/fc-v2/nuttx-config/nsh/defconfig @@ -85,7 +85,7 @@ CONFIG_IOB_NCHAINS=24 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/mro/ctrl-zero-f7-oem/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-f7-oem/nuttx-config/nsh/defconfig index d4cb06999b..cf531788f2 100644 --- a/boards/mro/ctrl-zero-f7-oem/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-f7-oem/nuttx-config/nsh/defconfig @@ -82,7 +82,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/mro/ctrl-zero-f7/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-f7/nuttx-config/nsh/defconfig index a15ab962cb..1afed883f5 100644 --- a/boards/mro/ctrl-zero-f7/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-f7/nuttx-config/nsh/defconfig @@ -82,7 +82,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/mro/ctrl-zero-h7-oem/nuttx-config/bootloader/defconfig b/boards/mro/ctrl-zero-h7-oem/nuttx-config/bootloader/defconfig index eff43cc1d4..ecd6495765 100644 --- a/boards/mro/ctrl-zero-h7-oem/nuttx-config/bootloader/defconfig +++ b/boards/mro/ctrl-zero-h7-oem/nuttx-config/bootloader/defconfig @@ -51,7 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=8 +CONFIG_FS_PROCFS_MAX_TASKS=8 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_PREALLOC_TIMERS=50 diff --git a/boards/mro/ctrl-zero-h7-oem/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-h7-oem/nuttx-config/nsh/defconfig index 1b47c38458..0bdb3ac056 100644 --- a/boards/mro/ctrl-zero-h7-oem/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-h7-oem/nuttx-config/nsh/defconfig @@ -84,7 +84,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/mro/ctrl-zero-h7/nuttx-config/bootloader/defconfig b/boards/mro/ctrl-zero-h7/nuttx-config/bootloader/defconfig index 5676469c9e..54b931d4fb 100644 --- a/boards/mro/ctrl-zero-h7/nuttx-config/bootloader/defconfig +++ b/boards/mro/ctrl-zero-h7/nuttx-config/bootloader/defconfig @@ -51,7 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=8 +CONFIG_FS_PROCFS_MAX_TASKS=8 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_PREALLOC_TIMERS=50 diff --git a/boards/mro/ctrl-zero-h7/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-h7/nuttx-config/nsh/defconfig index cf9b42070f..e8cf827f9a 100644 --- a/boards/mro/ctrl-zero-h7/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-h7/nuttx-config/nsh/defconfig @@ -84,7 +84,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/mro/pixracerpro/nuttx-config/bootloader/defconfig b/boards/mro/pixracerpro/nuttx-config/bootloader/defconfig index 3b89cb0c7a..06fcf69561 100644 --- a/boards/mro/pixracerpro/nuttx-config/bootloader/defconfig +++ b/boards/mro/pixracerpro/nuttx-config/bootloader/defconfig @@ -51,7 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=8 +CONFIG_FS_PROCFS_MAX_TASKS=8 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_PREALLOC_TIMERS=50 diff --git a/boards/mro/pixracerpro/nuttx-config/nsh/defconfig b/boards/mro/pixracerpro/nuttx-config/nsh/defconfig index 001d90b930..4e1a5712eb 100644 --- a/boards/mro/pixracerpro/nuttx-config/nsh/defconfig +++ b/boards/mro/pixracerpro/nuttx-config/nsh/defconfig @@ -82,7 +82,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/mro/x21-777/nuttx-config/nsh/defconfig b/boards/mro/x21-777/nuttx-config/nsh/defconfig index d83d22dc17..810fc89ca9 100644 --- a/boards/mro/x21-777/nuttx-config/nsh/defconfig +++ b/boards/mro/x21-777/nuttx-config/nsh/defconfig @@ -82,7 +82,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/nxp/ucans32k146/nuttx-config/canbootloader/defconfig b/boards/nxp/ucans32k146/nuttx-config/canbootloader/defconfig index 05f02bf57e..f721e5bed7 100644 --- a/boards/nxp/ucans32k146/nuttx-config/canbootloader/defconfig +++ b/boards/nxp/ucans32k146/nuttx-config/canbootloader/defconfig @@ -43,7 +43,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=0 +CONFIG_FS_PROCFS_MAX_TASKS=0 CONFIG_NAME_MAX=0 CONFIG_NUNGET_CHARS=0 CONFIG_NXFONTS_DISABLE_16BPP=y diff --git a/boards/nxp/ucans32k146/nuttx-config/nsh/defconfig b/boards/nxp/ucans32k146/nuttx-config/nsh/defconfig index 2ba10a7143..8359e45d29 100644 --- a/boards/nxp/ucans32k146/nuttx-config/nsh/defconfig +++ b/boards/nxp/ucans32k146/nuttx-config/nsh/defconfig @@ -52,7 +52,7 @@ CONFIG_LPUART0_TXDMA=y CONFIG_LPUART1_RXBUFSIZE=128 CONFIG_LPUART1_SERIAL_CONSOLE=y CONFIG_LPUART1_TXBUFSIZE=128 -CONFIG_MAX_TASKS=16 +CONFIG_FS_PROCFS_MAX_TASKS=16 CONFIG_MOTOROLA_SREC=y CONFIG_MTD=y CONFIG_MTD_PARTITION=y diff --git a/boards/px4/fmu-v5/nuttx-config/debug/defconfig b/boards/px4/fmu-v5/nuttx-config/debug/defconfig index 8223096ac1..b64efb2d59 100644 --- a/boards/px4/fmu-v5/nuttx-config/debug/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/debug/defconfig @@ -127,7 +127,7 @@ CONFIG_IDLETHREAD_STACKSIZE=864 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/px4/fmu-v5/nuttx-config/nsh/defconfig b/boards/px4/fmu-v5/nuttx-config/nsh/defconfig index 5470c81d86..8502b9254e 100644 --- a/boards/px4/fmu-v5/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/nsh/defconfig @@ -83,7 +83,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/px4/fmu-v5/nuttx-config/optimized/defconfig b/boards/px4/fmu-v5/nuttx-config/optimized/defconfig index 3411696770..c3111c9888 100644 --- a/boards/px4/fmu-v5/nuttx-config/optimized/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/optimized/defconfig @@ -84,7 +84,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=n -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig index 5406c200ed..20133e7fdb 100644 --- a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig @@ -84,7 +84,7 @@ CONFIG_IDLETHREAD_STACKSIZE=864 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/px4/fmu-v5/nuttx-config/uavcanv1/defconfig b/boards/px4/fmu-v5/nuttx-config/uavcanv1/defconfig index bda74b6546..5f093b9ff5 100644 --- a/boards/px4/fmu-v5/nuttx-config/uavcanv1/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/uavcanv1/defconfig @@ -85,7 +85,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/px4/fmu-v5x/nuttx-config/base_phy_DP83848C/defconfig b/boards/px4/fmu-v5x/nuttx-config/base_phy_DP83848C/defconfig index 0d2d718a71..cb762653ee 100644 --- a/boards/px4/fmu-v5x/nuttx-config/base_phy_DP83848C/defconfig +++ b/boards/px4/fmu-v5x/nuttx-config/base_phy_DP83848C/defconfig @@ -89,7 +89,7 @@ CONFIG_IPCFG_PATH="/fs/mtd_net" CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig index 1e2f342fbe..b47e09dbda 100644 --- a/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig @@ -89,7 +89,7 @@ CONFIG_IPCFG_PATH="/fs/mtd_net" CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/px4/fmu-v6u/nuttx-config/bootloader/defconfig b/boards/px4/fmu-v6u/nuttx-config/bootloader/defconfig index de1c00e94d..e37bc5581c 100644 --- a/boards/px4/fmu-v6u/nuttx-config/bootloader/defconfig +++ b/boards/px4/fmu-v6u/nuttx-config/bootloader/defconfig @@ -51,7 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=8 +CONFIG_FS_PROCFS_MAX_TASKS=8 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_PREALLOC_TIMERS=50 diff --git a/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig index 5e9a6cb9d2..32e762305a 100644 --- a/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig @@ -85,7 +85,7 @@ CONFIG_IOB_NCHAINS=24 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/px4/fmu-v6x/nuttx-config/bootloader/defconfig b/boards/px4/fmu-v6x/nuttx-config/bootloader/defconfig index 7ead868cb4..cbfe1c3285 100644 --- a/boards/px4/fmu-v6x/nuttx-config/bootloader/defconfig +++ b/boards/px4/fmu-v6x/nuttx-config/bootloader/defconfig @@ -51,7 +51,7 @@ CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y CONFIG_LIB_BOARDCTL=y -CONFIG_MAX_TASKS=8 +CONFIG_FS_PROCFS_MAX_TASKS=8 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_PREALLOC_TIMERS=50 diff --git a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig index 1d32cb5b38..8242b385a0 100644 --- a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig @@ -90,7 +90,7 @@ CONFIG_IPCFG_PATH="/fs/mtd_net" CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/boards/px4/io-v2/nuttx-config/nsh/defconfig b/boards/px4/io-v2/nuttx-config/nsh/defconfig index 324931beb6..cc8229fca7 100644 --- a/boards/px4/io-v2/nuttx-config/nsh/defconfig +++ b/boards/px4/io-v2/nuttx-config/nsh/defconfig @@ -28,7 +28,7 @@ CONFIG_FDCLONE_STDIO=y CONFIG_HAVE_CXX=y CONFIG_HAVE_CXXINITIALIZE=y CONFIG_IDLETHREAD_STACKSIZE=280 -CONFIG_MAX_TASKS=2 +CONFIG_FS_PROCFS_MAX_TASKS=2 CONFIG_MM_FILL_ALLOCATIONS=y CONFIG_MM_SMALL=y CONFIG_NAME_MAX=12 diff --git a/boards/spracing/h7extreme/nuttx-config/nsh/defconfig b/boards/spracing/h7extreme/nuttx-config/nsh/defconfig index d7145ca2a6..cea5698a97 100644 --- a/boards/spracing/h7extreme/nuttx-config/nsh/defconfig +++ b/boards/spracing/h7extreme/nuttx-config/nsh/defconfig @@ -83,7 +83,7 @@ CONFIG_IDLETHREAD_STACKSIZE=750 CONFIG_LIBC_FLOATINGPOINT=y CONFIG_LIBC_LONG_LONG=y CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=64 +CONFIG_FS_PROCFS_MAX_TASKS=64 CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y diff --git a/platforms/common/include/px4_platform_common/printload.h b/platforms/common/include/px4_platform_common/printload.h index e72b13633a..9bf9e7c80e 100644 --- a/platforms/common/include/px4_platform_common/printload.h +++ b/platforms/common/include/px4_platform_common/printload.h @@ -45,8 +45,8 @@ #include -#ifndef CONFIG_MAX_TASKS -#define CONFIG_MAX_TASKS 64 +#ifndef CONFIG_FS_PROCFS_MAX_TASKS +#define CONFIG_FS_PROCFS_MAX_TASKS 64 #endif struct print_load_s { @@ -57,7 +57,7 @@ struct print_load_s { uint64_t new_time{0}; uint64_t interval_start_time{0}; - uint64_t last_times[CONFIG_MAX_TASKS] {}; + uint64_t last_times[CONFIG_FS_PROCFS_MAX_TASKS] {}; float interval_time_us{0.f}; }; diff --git a/platforms/nuttx/src/px4/common/cpuload.cpp b/platforms/nuttx/src/px4/common/cpuload.cpp index 04582538c3..62c5c6205d 100644 --- a/platforms/nuttx/src/px4/common/cpuload.cpp +++ b/platforms/nuttx/src/px4/common/cpuload.cpp @@ -61,7 +61,7 @@ void cpuload_monitor_start() system_load.start_time = hrt_absolute_time(); - for (int i = 1; i < CONFIG_MAX_TASKS; i++) { + for (int i = 1; i < CONFIG_FS_PROCFS_MAX_TASKS; i++) { system_load.tasks[i].total_runtime = 0; system_load.tasks[i].curr_start_time = 0; } diff --git a/platforms/nuttx/src/px4/common/include/px4_platform/cpuload.h b/platforms/nuttx/src/px4/common/include/px4_platform/cpuload.h index 2fc8bb80a3..56b7d36945 100644 --- a/platforms/nuttx/src/px4/common/include/px4_platform/cpuload.h +++ b/platforms/nuttx/src/px4/common/include/px4_platform/cpuload.h @@ -48,7 +48,7 @@ struct system_load_taskinfo_s { struct system_load_s { uint64_t start_time{0}; - system_load_taskinfo_s tasks[CONFIG_MAX_TASKS] {}; + system_load_taskinfo_s tasks[CONFIG_FS_PROCFS_MAX_TASKS] {}; int total_count{0}; int running_count{0}; bool initialized{false}; diff --git a/platforms/nuttx/src/px4/common/print_load.cpp b/platforms/nuttx/src/px4/common/print_load.cpp index 3770f4ba8a..fa341c7824 100644 --- a/platforms/nuttx/src/px4/common/print_load.cpp +++ b/platforms/nuttx/src/px4/common/print_load.cpp @@ -81,7 +81,7 @@ void init_print_load(struct print_load_s *s) s->last_times[0] = system_load.tasks[0].total_runtime; sched_unlock(); - for (int i = 1; i < CONFIG_MAX_TASKS; i++) { + for (int i = 1; i < CONFIG_FS_PROCFS_MAX_TASKS; i++) { s->last_times[i] = 0; } @@ -142,12 +142,12 @@ void print_load_buffer(char *buffer, int buffer_length, print_load_callback_f cb float idle_load = 0.f; // create a copy of the runtimes because this could be updated during the print output - uint64_t total_runtime[CONFIG_MAX_TASKS] {}; + uint64_t total_runtime[CONFIG_FS_PROCFS_MAX_TASKS] {}; sched_lock(); print_state->new_time = hrt_absolute_time(); - for (int i = 0; i < CONFIG_MAX_TASKS; i++) { + for (int i = 0; i < CONFIG_FS_PROCFS_MAX_TASKS; i++) { if (system_load.tasks[i].valid) { total_runtime[i] = system_load.tasks[i].total_runtime; } @@ -182,7 +182,7 @@ void print_load_buffer(char *buffer, int buffer_length, print_load_callback_f cb print_state->total_user_time = 0; - for (int i = 0; i < CONFIG_MAX_TASKS; i++) { + for (int i = 0; i < CONFIG_FS_PROCFS_MAX_TASKS; i++) { sched_lock(); // need to lock the tcb access (but make it as short as possible) diff --git a/src/modules/load_mon/LoadMon.cpp b/src/modules/load_mon/LoadMon.cpp index d6f9089fd2..8bc818a80c 100644 --- a/src/modules/load_mon/LoadMon.cpp +++ b/src/modules/load_mon/LoadMon.cpp @@ -290,7 +290,7 @@ void LoadMon::stack_usage() } // Continue after last checked task next cycle - _stack_task_index = (_stack_task_index + 1) % CONFIG_MAX_TASKS; + _stack_task_index = (_stack_task_index + 1) % CONFIG_FS_PROCFS_MAX_TASKS; } #endif diff --git a/src/modules/logger/watchdog.cpp b/src/modules/logger/watchdog.cpp index c7328bd3ed..32e4f76fce 100644 --- a/src/modules/logger/watchdog.cpp +++ b/src/modules/logger/watchdog.cpp @@ -140,7 +140,7 @@ void watchdog_initialize(const pid_t pid_logger_main, const pthread_t writer_thr sched_lock(); // need to lock the tcb access - for (int i = 0; i < CONFIG_MAX_TASKS; i++) { + for (int i = 0; i < CONFIG_FS_PROCFS_MAX_TASKS; i++) { if (system_load.tasks[i].valid) { if (system_load.tasks[i].tcb->pid == pid_logger_writer) { watchdog_data.logger_writer_task_index = i;