Skip to content

[Custom Board] PX4 Spawn Reject (Errno 128) - Task Table Exhaustion on STM32H7 #26303

@mkeyno

Description

@mkeyno

I am bringing up a custom STM32H743VI board (PixEagle). The boot sequence fails early during the initialization of the Work Queue Manager. Specifically, px4_task_spawn_cmd fails with errno 128 when attempting to start the wq:manager thread.

Detailed Analysis

Based on debug instrumentation added to tasks.cpp, the system consistently fails when the task count reaches 4. The currently running tasks are:

Idle Task (PID 0)

hpwork (PID 1)

lpwork (PID 2)

nsh_main (PID 4)

Total: 4. Any attempt to spawn the 5th task (the wq:manager) is rejected by the NuttX kernel.

I have verified that there is ample heap available (~950KB free), so this is not a memory exhaustion issue (ENOMEM), but a task slot limitation.

Relevant Logs

The Configuration Problem
I have searched the build directory and .config for CONFIG_MAX_TASKS. It appears to be falling back to a default value (likely 4) because it is not explicitly defined in the board’s defconfig. Even though CONFIG_TASK_NAME_SIZE is set, the physical task limit is preventing the boot sequence from proceeding to the sensor drivers and the commander.

Source Code Reference
The board files and instrumented logic can be found here:

https://github.com/mkeyno/pixeagle

debug log output

APLLCFG:0x00bf0c8c
Clk: PLL1 OK
SYSCLK:480MHz
[I2C-CLK] Configuring I2C clocks…
[I2C-CLK] Before: D2CCIP2R=0x00302000 D3CCIPR=0x00000200
[I2C-CLK] After: D2CCIP2R=0x00202000 D3CCIPR=0x00000200
[I2C-CLK] I2C1/2/3 source: HSI (2)
[I2C-CLK] I2C4 source: HSI (2)
stm32_boardinitialize done (USB deferred to late init)
DE
nx_start: Entry
stm32_dumpnvic: NVIC (initial, irq=166):
stm32_dumpnvic: INTCTRL: 00000000 VECTAB: 08020000
stm32_dumpnvic: IRQ ENABLE: 00000000 00000000 00000000
stm32_dumpnvic: SYSH_PRIO: 00808080 70000000 80800080
stm32_dumpnvic: IRQ PRIO: 80808080 80808080 80808080 80808080
stm32_dumpnvic: 80808080 80808080 80808080 80808080
stm32_dumpnvic: 80808080 80808080 80808080 80808080
stm32_dumpnvic: 80808080 80808080 80808080 80808080
stm32_dumpnvic: 80808080 80808080 80808080 80808080
stm32_dumpnvic: 80808080 80808080 80808080 80808080
stm32_dumpnvic: 80808080 80808080 80808080 80808080
builtin_initialize: Registering Builtin Loader
arm_dma_initialize: Initialize DMA
uart_register: Registering /dev/console
uart_register: Registering /dev/ttyS0
uart_register: Registering /dev/ttyS1
uart_register: Registering /dev/ttyS2
uart_register: Registering /dev/ttyS3
uart_register: Registering /dev/ttyS4
uart_register: Registering /dev/ttyS5
work_start_highpri: Starting high-priority kernel worker thread(s)
work_start_lowpri: Starting low-priority kernel worker thread(s)
up_release_pending: From TCB=0x240048e4
nx_start_application: Starting init thread
nxsig_tcbdispatch: TCB=0x240048e4 signo=4 code=5 value=0 mask=00000000
up_exit: TCB=0x380019b0 exiting
ramdisk_register: buffer: 0x81619ed nsectors: 16 sectsize: 64
nsh_romfsetc: Mounting ROMFS filesystem at target=/etc with source=/dev/ram0
find_blockdriver: pathname=“/dev/ram0”
romfs_bind: Entry
rd_geometry: Entry
rd_geometry: available: true mediachanged: false writeenabled: false
rd_geometry: nsectors: 16 sectorsize: 64
rd_ioctl: Entry
rd_ioctl: ppv: 0x81619ed
[BOOT-1] PixEagle Init, SP=0x380034cb
pthread_mutex_timedlock: mutex=0x240005fc
pthread_mutex_timedlock: Returning 0
pthread_mutex_unlock: mutex=0x240005fc
pthread_mutex_unlock: Returning 0
[BOOT-2] Enabling sensor power…
[BOOT-3] Initializing SPI buses…
[BOOT-4] Configuring FRAM…
[SPI2-INIT-1] Configuring GPIO clocks and CS pins…
[GPIO-1] Enabling GPIOB and GPIOD clocks…
[GPIO-2] Configuring CS pins as outputs…
[GPIO-3] GPIOD_MODER=0x001f7ffa GPIOD_ODR=0x00000480 (PD10=1)
[GPIO-4] GPIOB_MODER=0xfa7ffe9f GPIOB_ODR=0x00000804 (PB11=1)
[SPI2-INIT-2] Enabling SPI2 clock…
[SPI2-INIT-3] Pre-reset SR: 0x00001002
[SPI2-INIT-4] Forcing hardware reset…
[SPI2-INIT-5] Post-reset SR: 0x00001002 SUSP OK
[SPI2-INIT-6] Calling stm32_spibus_initialize(2)…
[SPI2] After IFCR SUSPC clear SR=0x00001002 (SUSP cleared - good)
spi_setfrequency: Frequency 400000->750000
spi_dumpregs: CR1: 0x00001001 CFG1: 0x70070007 CFG2: 0x84400000
spi_dumpregs: IER: 0x00000000 SR: 0x00001002 I2SCFGR: 0x00000000
[SPI2-INIT-7] Bus init OK, spi2=0x24000be4
[SPI2-INIT-8] Configuring SPI2…
[SPI2-INIT-9] Lock acquired
spi_setmode: mode=0
[SPI2-INIT-10] Mode set
spi_setbits: nbits=8
[SPI2-INIT-11] Bits set
[SPI2-INIT-12] Freq set
[SPI2-INIT-13] Lock released
[POST-INIT] === SPI2 DUMP ===
CR1 = 0x00001001
CR2 = 0x00000000
CFG1 = 0x70070007
CFG2 = 0x84400000
SR = 0x00001002
IER = 0x00000000
GPIOB_MODER = 0xaa6ffe9f
GPIOB_ODR = 0x00000804 (PB11_SD=1)
GPIOD_ODR = 0x00000480 (PD10_FRAM=1)
RCC_APB1LENR = 0x00a8c000 (SPI2EN=1)
[SPI2-INIT-COMPLETE] Success
[FRAM-DBG] verify_fram_spi2 entry spi2=0x24000be4
[FRAM-DBG] ops=0x81b9a8c
[FRAM-DBG] ops->lock = 0x8151511
[FRAM-DBG] ops->select = 0x815106d
[FRAM-DBG] ops->status = 0x815109d
[FRAM-DBG] ops->setfrequency = 0x8151541
[FRAM-DBG] ops->setmode = 0x8151735
[FRAM-DBG] ops->setbits = 0x81516e9
[FRAM-DBG] ops->status(spi2, SPIDEV_FLASH(0)) = 0x01
[FRAM-DBG] calling ops->lock(spi2, true) → 0
[BEFORE-CS-ASSERT] === SPI2 DUMP ===
CR1 = 0x00001001
CR2 = 0x00000000
CFG1 = 0x70070007
CFG2 = 0x84400000
SR = 0x00001002
IER = 0x00000000
GPIOB_MODER = 0xaa6ffe9f
GPIOB_ODR = 0x00000804 (PB11_SD=1)
GPIOD_ODR = 0x00000480 (PD10_FRAM=1)
RCC_APB1LENR = 0x00a8c000 (SPI2EN=1)
[FRAM-DBG] About to call ops->select(spi2, SPIDEV_FLASH(0), true) → 0x815106d
[AFTER-CS-ASSERT] === SPI2 DUMP ===
CR1 = 0x00001001
CR2 = 0x00000000
CFG1 = 0x70070007
CFG2 = 0x84400000
SR = 0x00001002
IER = 0x00000000
GPIOB_MODER = 0xaa6ffe9f
GPIOB_ODR = 0x00000804 (PB11_SD=1)
GPIOD_ODR = 0x00000080 (PD10_FRAM=0)
RCC_APB1LENR = 0x00a8c000 (SPI2EN=1)
spi_send: Sent: 9f Return: ff Status: 02
spi_exchange: txbuffer=0 rxbuffer=0x380034cc nwords=9
spi_send: Sent: ff Return: 7f Status: 02
spi_send: Sent: ff Return: 7f Status: 02
spi_send: Sent: ff Return: 7f Status: 02
spi_send: Sent: ff Return: 7f Status: 02
spi_send: Sent: ff Return: 7f Status: 02
spi_send: Sent: ff Return: 7f Status: 02
spi_send: Sent: ff Return: c2 Status: 02
spi_send: Sent: ff Return: 21 Status: 02
spi_send: Sent: ff Return: 08 Status: 02
[FRAM-DBG] FRAM ID: 7F 7F 7F 7F 7F 7F C2 21 08
[FRAM-DBG] ID match - FRAM OK
[BOOT-5] FRAM OK, attempting mount…
[MTD-1] Calling ramtron_initialize…
ramtron_initialize: dev: 0x24000be4
ramtron_readid: priv: 0x38001aa0
spi_setmode: mode=3
spi_setbits: nbits=8
spi_setfrequency: Frequency 0->750000
spi_send: Sent: 9f Return: ff Status: 1002
spi_send: Sent: a5 Return: 7f Status: 1002
spi_send: Sent: a5 Return: 7f Status: 1002
spi_send: Sent: a5 Return: 7f Status: 1002
spi_send: Sent: a5 Return: 7f Status: 1002
spi_send: Sent: a5 Return: 7f Status: 1002
spi_send: Sent: a5 Return: 7f Status: 1002
spi_send: Sent: a5 Return: c2 Status: 1002
spi_send: Sent: a5 Return: 21 Status: 1002
spi_send: Sent: a5 Return: 08 Status: 1002
ramtron_readid: RAMTRON FM25V01A of size 16384 bytes (mf:7f mem:c2 cap:21 part:08)
ramtron_initialize: Return 0x38001aa0
[MTD-2] ramtron_initialize OK, mtd=0x38001aa0
[MTD-3] MTD registered as /dev/mtd0
find_blockdriver: pathname=“/dev/mtd0”
find_blockdriver: /dev/mtd0 is a MTD
nx_mount: ERROR: Failed to find MTD based file system nxffs
[MTD-4] Direct mount failed (-19), trying format…
find_blockdriver: pathname=“/dev/mtd0”
find_blockdriver: /dev/mtd0 is a MTD
nx_mount: ERROR: Failed to find MTD based file system nxffs
[MTD-5] NXFFS mount failed: -19
[MTD-6] PX4 can still use /dev/mtd0 directly for params
[BOOT-6] Initializing SD card…
spi_setmode: mode=0
spi_setbits: nbits=8
spi_setfrequency: Frequency 400000->750000
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
mmcsd_mediainitialize: Send CMD0
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: 40 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 95 Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 01 Status: 02
mmcsd_sendcmd: CMD0[00000000] R1=01
mmcsd_mediainitialize: Card is in IDLE state
mmcsd_mediainitialize: Send CMD8
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: 48 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 01 Return: ff Status: 02
spi_send: Sent: aa Return: ff Status: 02
spi_send: Sent: 87 Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 01 Status: 02
spi_send: Sent: ff Return: 00 Status: 02
spi_send: Sent: ff Return: 00 Status: 02
spi_send: Sent: ff Return: 01 Status: 02
spi_send: Sent: ff Return: aa Status: 02
mmcsd_sendcmd: CMD8[000001aa] R1=01 R7=000001aa
mmcsd_mediainitialize: 0. Send CMD55/ACMD41
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: 77 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 01 Status: 02
mmcsd_sendcmd: CMD55[00000000] R1=01
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: 69 Return: ff Status: 02
spi_send: Sent: 40 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Stati_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 01 Status: 02
mmcsd_sendcmd: CMD41[40000000] R1=01
mmcsd_mediainitialize: 76. Send CMD55/ACMD41
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: 77 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 01 Status: 02
mmcsd_sendcmd: CMD55[00000000] R1=01
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: 69 Return: ff Status: 02
spi_send: Sent: 40 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 01 Status: 02
mmcsd_sendcmd: CMD41[40000000] R1=01
mmcsd_mediainitialize: 152. Send CMD55/ACMD41
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: 77 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 01 Status: 02
mmcsd_sendcmd: CMD55[00000000] R1=01
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: 69 Return: ff Status: 02
spi_send: Sent: 40 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 00 Status: 02
mmcsd_sendcmd: CMD41[40000000] R1=00
mmcsd_mediainitialize: Send CMD58
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: 7a Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 00 Status: 02
spi_send: Sent: ff Return: c0 Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 80 Status: 02
spi_send: Sent: ff Return: 80 Status: 02
mmcsd_sendcmd: CMD58[00000000] R1=00 OCR=c0ff8080
mmcsd_mediainitialize: OCR: c0ff8080
mmcsd_mediainitialize: Identified SD ver2 card/with block access
mmcsd_mediainitialize: Get CSD
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: 49 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: 00 Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: ff Status: 02
spi_send: Sent: ff Return: 00 Status: 02
mmcsd_sendcmd: CMD9[00000000] R1=00
spi_send: Sent: ff Return: ff Status: 02
mmcsd_getcardinfo: 0. SPI send returned ff
spi_send: Sent: ff Return: ff Status: 02
mmcsd_getcardinfo: 1. SPI send returned ff
spi_send: Sent: ff Return: fe Status: 02
mmcsd_getcardinfo: 2. SPI send returned fe
spi_send: Sent: ff Return: 40 Status: 02
spi_send: Sent: ff Return: 0e Status: 02
spi_send: Sent: ff Return: 00 Status: 02
spi_send: Sent: ff Return: 32 Status: 02
spi_send: Sent: ff Return: 5b Status: 02
spi_send: Sent: ff Return: 59 Status: 02
spi_send: Sent: ff Return: 00 Status: 02
spi_send: Sent: ff Return: 00 Status: 02
spi_send: Sent: ff Return: f0 Status: 02
spi_send: Sent: ff Return: 0f Status: 02
spi_send: Sent: ff Return: 7f Status: 02
spi_send: Sent: ff Return: 80 Status: 02
spi_send: Sent: ff Return: 0a Status: 02
spi_send: Sent: ff Return: 40 Status: 02
spi_send: Sent: ff Return: 40 Status: 02
spi_send: Sent: ff Return: 01 Status: 02
spi_send: Sent: ff Return: 5e Status: 02
spi_send: Sent: ff Return: d4 Status: 02
mmcsd_dmpcsd: CSD
mmcsd_dmpcsd: CSD_STRUCTURE: 1.1
mmcsd_dmpcsd: TAAC:
mmcsd_dmpcsd: TIME_VALUE: 0x01
mmcsd_dmpcsd: TIME_UNIT: 0x06
mmcsd_dmpcsd: NSAC: 0x00
mmcsd_dmpcsd: TRAN_SPEED:
mmcsd_dmpcsd: TIME_VALUE: 0x06
mmcsd_dmpcsd: RATE_UNIT: 0x02
mmcsd_dmpcsd: CCC: 0x5b5
mmcsd_dmpcsd: READ_BL_LEN: 9
mmcsd_dmpcsd: READ_BL_PARTIAL: 0
mmcsd_dmpcsd: WRITE_BLK_MISALIGN: 0
mmcsd_dmpcsd: READ_BLK_MISALIGN: 0
mmcsd_dmpcsd: DSR_IMP: 0
mmcsd_dmpcsd: C_SIZE: 61455
mmcsd_dmpcsd: VDD_R_CURR_MIN: 7
mmcsd_dmpcsd: VDD_R_CURR_MAX: 6
mmcsd_dmpcsd: VDD_W_CURR_MIN: 7
mmcsd_dmpcsd: VDD_W_CURR_MAX: 6
mmcsd_dmpcsd: C_SIZE_MULT: 8
mmcsd_dmpcsd: SD ER_BLK_EN: 1
mmcsd_dmpcsd: SD SECTOR_SIZE: 127
mmcsd_dmpcsd: SD WP_GRP_SIZE: 0
mmcsd_dmpcsd: WP_GRP_EN: 0
mmcsd_dmpcsd: R2W_FACTOR: 2
mmcsd_dmpcsd: WRITE_BL_LEN: 9
mmcsd_dmpcsd: WRITE_BL_PARTIAL: 0
mmcsd_dmpcsd: FILE_FORMAT_GROUP: 0
mmcsd_dmpcsd: COPY: 1
mmcsd_dmpcsd: PERM_WRITE_PROTECT: 0
mmcsd_dmpcsd: TMP_WRITE_PROTECT: 0
mmcsd_dmpcsd: FILE_FORMAT: 0
mmcsd_dmpcsd: CRC: 00
mmcsd_decodecsd: SPI Frequency
mmcsd_decodecsd: Maximum: 25000000 Hz
mmcsd_decodecsd: Actual: 750000 Hz
mmcsd_decodecsd: Read access time: 101 ticks
mmcsd_decodecsd: Write access time: 251 ticks
mmcsd_decodecsd: Sector size: 512
mmcsd_decodecsd: Number of sectors: 62930944
spi_send: Sent: ff Return: ff Status: 02
mmcsd_spislotinitialize: mmcsd_mediainitialize returned OK
[BOOT-7] Configuring USB (late init)…
[boot] HSI48 OK
[boot] USB clock (HSI48 + CRS) OK
setup_usb: RCC_CR=0x3F03F035 D2CCIP2R=0x00302000
[BOOT-8] Starting USB device stack…
[BOOT-9] Starting PX4 platform…
[MEM-DBG] MPU_CTRL=0x00000000
[MEM-DBG] SCB_CACR=0x00000000
[MEM-DBG] AXI_SRAM @ 0x24000000 test…
[MEM-DBG] Wrote 0xDEADBEEF, read back 0xdeadbeef
[WQ-DEBUG] About to start px4_platform_init()
P_cpuload_initialize_once[OLED DEBUG] D2CCIP2R: 3153920
[OLED DEBUG] D3CCIPR: 512
[OLED DEBUG] RCC_CR: 1057222709
[OLED DEBUG] step 6: Bus 1 Init Start
[OLED DEBUG] PerBus D2CCIP2R: 3153920
[OLED DEBUG] PerBus RCC_CR: 1057222709
n[OLED DEBUG] step 6: Bus 3 Init Start
[OLED DEBUG] PerBus D2CCIP2R: 3153920
[OLED DEBUG] PerBus RCC_CR: 1057222709
x[OLED DEBUG] step 6: Bus 4 Init Start
[OLED DEBUG] PerBus D3CCIPR: 512
[OLED DEBUG] PerBus RCC_CR: 1057222709
_binfs_bind: Entry
[TIMER-DEBUG] Testing HRT Timer…
[TIMER-DEBUG] T1: 45480, T2: 49129, Diff: 3649
[TIMER-DEBUG] SUCCESS: Timer is running.
[WQ-DBG] Flags on entry: should_exit=0 running=0
[WQ-DBG] Spawning wq:manager task… (stack=4096 prio=250) heap_free=951536 SCHED_FIFO=1 max=255 min=1 requested=250
[MEM-DUMP] === Memory dump: pre-spawn ===
[MEM-DUMP] mallinfo: arena=964144 ordblks=5 uordblks=12608 fordblks=951536
[MEM-DUMP] Attempting mm_foreach style region dump (if supported)…
[MEM-DUMP] Task list (if nxsched_foreach available):
[MEM-DUMP] PID= 0 PRI= 0 STACK_SIZE= 1000 NAME=Idle Task
[MEM-DUMP] PID= 1 PRI=249 STACK_SIZE= 1224 NAME=hpwork
[MEM-DUMP] PID= 2 PRI= 50 STACK_SIZE= 1576 NAME=lpwork
[MEM-DUMP] PID= 4 PRI=100 STACK_SIZE= 2000 NAME=nsh_main
[MEM-DUMP] Total tasks enumerated: 4
[MEM-DUMP] === End memory dump: pre-spawn ===
[SPAWN-IN] Name: wq:manager, Prio: 250, Stack: 4096, Sch: 1
[SPAWN-IN] Caller return address: 0x81542af
[SPAWN-IN] Caller backtrace (8 frames):
[0] 0x803a86e
[1] 0x814f05a
[2] 0x8022018
[3] 0x81542aa
[4] 0x814f3d4
[5] 0x8022018
[6] 0x814df1c
[7] 0x803050e

Args: NULL
[SPAWN-REJECT] wq:manager failed!
Reason Code (errno): 128
[KERN-TCB] PID=0 PRI=0 NAME=Idle Task
[KERN-TCB] PID=1 PRI=249 NAME=hpwork
[KERN-TCB] PID=2 PRI=50 NAME=lpwork
[KERN-TCB] PID=4 PRI=100 NAME=nsh_main
[KERN-TCB] total kernel tasks: 4
Depth: Task Table Full (CONFIG_MAX_TASKS reached).
[WQ-DBG] px4_task_spawn_cmd failed: ret=-1 errno=128 (Unknown error)
[MEM-DUMP] === Memory dump: spawn-failed ===
[MEM-DUMP] mallinfo: arena=964144 ordblks=6 uordblks=12576 fordblks=951568
[MEM-DUMP] Attempting mm_foreach style region dump (if supported)…
[MEM-DUMP] Task list (if nxsched_foreach available):
[MEM-DUMP] PID= 0 PRI= 0 STACK_SIZE= 1000 NAME=Idle Task
[MEM-DUMP] PID= 1 PRI=249 STACK_SIZE= 1224 NAME=hpwork
[MEM-DUMP] PID= 2 PRI= 50 STACK_SIZE= 1576 NAME=lpwork
[MEM-DUMP] PID= 4 PRI=100 STACK_SIZE= 2000 NAME=nsh_main
[MEM-DUMP] Total tasks enumerated: 4
[MEM-DUMP] === End memory dump: spawn-failed ===
[WQ-DBG] Attempting fallback spawn (stack=2048 prio=128)…
[SPAWN-IN] Name: wq:manager, Prio: 128, Stack: 2048, Sch: 1
[SPAWN-IN] Caller return address: 0x815433f
[SPAWN-IN] Caller backtrace (8 frames):
[0] 0x803a86e
[1] 0x814f05a
[2] 0x8022cde
[3] 0x8021ffc
[4] 0x815433a
[5] 0x814f3d4
[6] 0x8022018
[7] 0x814df1c
Args: NULL
[SPAWN-REJECT] wq:manager failed!
Reason Code (errno): 128
[KERN-TCB] PID=0 PRI=0 NAME=Idle Task
[KERN-TCB] PID=1 PRI=249 NAME=hpwork
[KERN-TCB] PID=2 PRI=50 NAME=lpwork
[KERN-TCB] PID=4 PRI=100 NAME=nsh_main
[KERN-TCB] total kernel tasks: 4
Depth: Task Table Full (CONFIG_MAX_TASKS reached).
[WQ-DBG] Fallback spawn also failed: ret=-1 errno=128 (Unknown error)
[MEM-DUMP] === Memory dump: fallback-spawn-failed ===
[MEM-DUMP] mallinfo: arena=964144 ordblks=6 uordblks=12576 fordblks=951568
[MEM-DUMP] Attempting mm_foreach style region dump (if supported)…
[MEM-DUMP] Task list (if nxsched_foreach available):
[MEM-DUMP] PID= 0 PRI= 0 STACK_SIZE= 1000 NAME=Idle Task
[MEM-DUMP] PID= 1 PRI=249 STACK_SIZE= 1224 NAME=hpwork
[MEM-DUMP] PID= 2 PRI= 50 STACK_SIZE= 1576 NAME=lpwork
[MEM-DUMP] PID= 4 PRI=100 STACK_SIZE= 2000 NAME=nsh_main
[MEM-DUMP] Total tasks enumerated: 4
[MEM-DUMP] === End memory dump: fallback-spawn-failed ===
[TASK-DUMP] === All Running Tasks/Threads ===
[TASK-DUMP] PID PRI STACK_SIZE NAME
[TASK-DUMP] 0 0 1000 Idle Task
[TASK-DUMP] 1 249 1224 hpwork
[TASK-DUMP] 2 50 1576 lpwork
[TASK-DUMP] 4 100 2000 nsh_main
[TASK-DUMP] Total tasks: 4
[TASK-DUMP] ==================================
start: CPU0: Beginning Idle Loop

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions