feat(platforms): upgrade NuttX to 12.12.0

bootloader: update main prototype for NuttX 12.12.0

platforms/nuttx: Add wrapper for queue.h

For some reason the queue.h header was moved, add this wrapper so
posix and nuttx builds can both still use #include <queue.h>

Fix print_load to be compatible with upstream NuttX

Also Change tg_filelist -> tg_fdlist as per new NuttX

Co-authored-by: Ville Juven <ville.juven@unikie.com>
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This commit is contained in:
Peter van der Perk
2026-01-05 13:34:04 +01:00
parent ad695a6e6f
commit d984305aae
23 changed files with 198 additions and 110 deletions
+1 -1
View File
@@ -351,7 +351,7 @@ else()
)
target_link_libraries(nuttx_c INTERFACE nuttx_drivers)
target_link_libraries(nuttx_drivers INTERFACE nuttx_c)
target_link_libraries(nuttx_drivers INTERFACE nuttx_c nuttx_fs)
target_link_libraries(nuttx_xx INTERFACE nuttx_c)
target_link_libraries(nuttx_fs INTERFACE nuttx_c)
+42 -12
View File
@@ -44,6 +44,22 @@ endif
include $(TOPDIR)/.config
include $(TOPDIR)/tools/Config.mk
# Include toolchain definitions based on architecture
# This is required for NuttX 12.x which moved toolchain-specific flags to Toolchain.defs
ifeq ($(CONFIG_ARCH_ARMV7M),y)
include $(TOPDIR)/arch/arm/src/armv7-m/Toolchain.defs
else ifeq ($(CONFIG_ARCH_ARMV7A),y)
include $(TOPDIR)/arch/arm/src/armv7-a/Toolchain.defs
else ifeq ($(CONFIG_ARCH_ARMV7R),y)
include $(TOPDIR)/arch/arm/src/armv7-r/Toolchain.defs
else ifeq ($(CONFIG_ARCH_ARMV8M),y)
include $(TOPDIR)/arch/arm/src/armv8-m/Toolchain.defs
else ifeq ($(CONFIG_ARCH_ARMV8R),y)
include $(TOPDIR)/arch/arm/src/armv8-r/Toolchain.defs
else ifeq ($(CONFIG_ARCH_ARMV6M),y)
include $(TOPDIR)/arch/arm/src/armv6-m/Toolchain.defs
endif
# Replace each space separated word in the string that contains "cygdrive"
# with the windows path and escaped backslashes
# e.g. [hello -I /cygdrive/c -I/cygdrive/c] -> [hello -I C:\\ ]
@@ -57,13 +73,35 @@ fi \
)))
endef
CINCPATH := $(shell $(INCDIR) -s "$(CC)" $(TOPDIR)$(DELIM)include)
CXXINCPATH := $(shell $(INCDIR) -s "$(CC)" $(TOPDIR)$(DELIM)include$(DELIM)cxx)
# Define compilers first, before they are used in CINCPATH calculation
CC = ${CMAKE_C_COMPILER}
CXX = ${CMAKE_CXX_COMPILER}
CPP = ${CMAKE_C_COMPILER} -E
LD = ${CMAKE_LD}
STRIP = ${CMAKE_STRIP} --strip-unneeded
AR = ${CMAKE_AR} rcs
NM = ${CMAKE_NM}
OBJCOPY = ${CMAKE_OBJCOPY}
OBJDUMP = ${CMAKE_OBJDUMP}
CINCPATH := $(INCSYSDIR_PREFIX)$(TOPDIR)$(DELIM)include
CXXINCPATH := $(INCSYSDIR_PREFIX)$(TOPDIR)$(DELIM)include$(DELIM)cxx
ARCHINCLUDES += $(CINCPATH)
ARCHXXINCLUDES += $(CINCPATH) $(CXXINCPATH)
ARCHSCRIPT = -T$(BOARD_DIR)$(DELIM)scripts$(DELIM)flash.ld
# PX4 boards may include stm32_rcc.h from board.h. That header is arch-private
# and lives in arch/arm/src/stm32f7, not in nuttx/include. The recursive NuttX
# kernel/lib builds (e.g. sched/) use this generated Make.defs, so the include
# path must be provided here.
ifeq ($(CONFIG_ARCH_CHIP_STM32F7),y)
ARCHINCLUDES += -I $(TOPDIR)/arch/$(CONFIG_ARCH)/src/stm32f7 \
-I $(TOPDIR)/arch/$(CONFIG_ARCH)/src/common
ARCHXXINCLUDES += -I $(TOPDIR)/arch/$(CONFIG_ARCH)/src/stm32f7 \
-I $(TOPDIR)/arch/$(CONFIG_ARCH)/src/common
endif
ifeq ($(CONFIG_BOARD_USE_PROBES),y)
ARCHINCLUDES += -I $(TOPDIR)/arch/$(CONFIG_ARCH)/src/$(CONFIG_ARCH_CHIP) -I $(TOPDIR)/arch/$(CONFIG_ARCH)/src/common
ARCHXXINCLUDES += -I $(TOPDIR)/arch/$(CONFIG_ARCH)/src/$(CONFIG_ARCH_CHIP) -I $(TOPDIR)/arch/$(CONFIG_ARCH)/src/common
@@ -74,16 +112,6 @@ ifneq (, $(findstring CYGWIN, $(shell uname)))
ARCHXXINCLUDES := $(call cygwin_to_windows_paths,$(ARCHXXINCLUDES))
endif
CC = ${CMAKE_C_COMPILER}
CXX = ${CMAKE_CXX_COMPILER}
CPP = ${CMAKE_C_COMPILER} -E
LD = ${CMAKE_LD}
STRIP = ${CMAKE_STRIP} --strip-unneeded
AR = ${CMAKE_AR} rcs
NM = ${CMAKE_NM}
OBJCOPY = ${CMAKE_OBJCOPY}
OBJDUMP = ${CMAKE_OBJDUMP}
ARCHCCVERSION = $(shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q')
ARCHCCMAJOR = $(shell echo $(ARCHCCVERSION) | cut -d'.' -f1)
@@ -104,7 +132,9 @@ FLAGS = $(MAXOPTIMIZATION) -g2 \
-Wall \
-Wextra \
-Wlogical-op \
-Wno-builtin-declaration-mismatch \
-Wno-cpp \
-Wno-format \
-Wno-format-truncation \
-Wno-maybe-uninitialized \
-Wno-missing-field-initializers \
+38
View File
@@ -0,0 +1,38 @@
/****************************************************************************
*
* Copyright (C) 2026 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.
*
****************************************************************************/
#pragma once
/* Wrapper for nuttx/queue.h */
#include <nuttx/queue.h>
+1
View File
@@ -78,6 +78,7 @@ function(px4_os_add_flags)
${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/nuttx/arch/${CONFIG_ARCH}/src/common
${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/apps/include
${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/include
)
@@ -694,7 +694,7 @@ arch_do_jump(const uint32_t *app_base)
}
int
bootloader_main(void)
bootloader_main(int argc, char *argv[])
{
bool try_boot = true; /* try booting before we drop to the bootloader */
unsigned timeout = BOOTLOADER_DELAY; /* if nonzero, drop out of the bootloader after this time */
@@ -637,7 +637,7 @@ arch_do_jump(const uint32_t *app_base)
}
int
bootloader_main(void)
bootloader_main(int argc, char *argv[])
{
bool try_boot = true; /* try booting before we drop to the bootloader */
unsigned timeout = BOOTLOADER_DELAY; /* if nonzero, drop out of the bootloader after this time */
@@ -40,7 +40,7 @@
#include <board_config.h>
#ifdef CONFIG_BOARD_CRASHDUMP
#ifdef CONFIG_BOARD_CRASHDUMP_CUSTOM
#include <stdio.h>
#include <stdbool.h>
@@ -260,20 +260,23 @@ static void copy_reverse(stack_word_t *dest, stack_word_t *src, int size)
static uint32_t *__attribute__((noinline)) __ebss_addr(void)
{
return &_ebss;
return (uint32_t *)(uintptr_t)&_ebss;
}
#else
static uint32_t *__attribute__((noinline)) __sdata_addr(void)
{
return &_sdata;
return (uint32_t *)(uintptr_t)&_sdata;
}
#endif
__EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const char *filename, int lineno)
__EXPORT void board_crashdump(uintptr_t sp, FAR struct tcb_s *tcb,
FAR const char *filename, int lineno,
FAR const char *msg, FAR void *regs)
{
#ifndef BOARD_CRASHDUMP_RESET_ONLY
/* We need a chunk of ram to save the complete context in.
@@ -319,7 +322,7 @@ __EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const char
* fault.
*/
pdump->info.current_regs = (uintptr_t) CURRENT_REGS;
pdump->info.current_regs = (uintptr_t) regs;
/* Save Context */
@@ -346,11 +349,11 @@ __EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const char
* the users context
*/
if (CURRENT_REGS) {
pdump->info.stacks.interrupt.sp = currentsp;
if (regs) {
pdump->info.stacks.interrupt.sp = sp;
pdump->info.flags |= (eRegsPresent | eUserStackPresent | eIntStackPresent);
memcpy(pdump->info.regs, (void *)CURRENT_REGS, sizeof(pdump->info.regs));
memcpy(pdump->info.regs, (void *)regs, sizeof(pdump->info.regs));
pdump->info.stacks.user.sp = pdump->info.regs[REG_R13];
} else {
@@ -358,7 +361,7 @@ __EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const char
/* users context */
pdump->info.flags |= eUserStackPresent;
pdump->info.stacks.user.sp = currentsp;
pdump->info.stacks.user.sp = sp;
}
if (pdump->info.pid == 0) {
@@ -442,4 +445,4 @@ __EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const char
board_reset(CONFIG_BOARD_ASSERT_RESET_VALUE);
}
#endif /* CONFIG_BOARD_CRASHDUMP */
#endif /* CONFIG_BOARD_CRASHDUMP_CUSTOM */
@@ -305,72 +305,66 @@ static void mavlink_usb_check(void *arg)
else if (launch_passthru) {
sched_lock();
exec_argv = (char **)gps_argv;
exec_builtin(exec_argv[0], exec_argv, nullptr, 0);
sched_unlock();
exec_argv = (char **)passthru_argv;
}
exec_builtin(exec_argv[0], exec_argv, nullptr);
#endif
sched_lock();
sched_lock();
if (exec_builtin(exec_argv[0], exec_argv, nullptr, 0) > 0) {
usb_auto_start_state = UsbAutoStartState::connected;
if (exec_builtin(exec_argv[0], exec_argv, nullptr) > 0) {
} else {
usb_auto_start_state = UsbAutoStartState::disconnecting;
}
} else {
usb_auto_start_state = UsbAutoStartState::disconnecting;
sched_unlock();
}
sched_unlock();
}
}
}
} else {
// cleanup
if (ttyacm_fd >= 0) {
close(ttyacm_fd);
ttyacm_fd = -1;
}
usb_auto_start_state = UsbAutoStartState::disconnecting;
}
} else {
// cleanup
if (ttyacm_fd >= 0) {
close(ttyacm_fd);
ttyacm_fd = -1;
break;
case UsbAutoStartState::connected:
if (!vbus_present && !vbus_present_prev) {
sched_lock();
static const char app[] {"mavlink"};
static const char *stop_argv[] {"mavlink", "stop", "-d", USB_DEVICE_PATH, NULL};
exec_builtin(app, (char **)stop_argv, NULL, 0);
sched_unlock();
usb_auto_start_state = UsbAutoStartState::disconnecting;
}
usb_auto_start_state = UsbAutoStartState::disconnecting;
break;
case UsbAutoStartState::disconnecting:
// serial disconnect if unused
serdis_main(0, NULL);
usb_auto_start_state = UsbAutoStartState::disconnected;
break;
}
}
break;
vbus_present_prev = vbus_present;
case UsbAutoStartState::connected:
if (!vbus_present && !vbus_present_prev) {
sched_lock();
static const char app[] {"mavlink"};
static const char *stop_argv[] {"mavlink", "stop", "-d", USB_DEVICE_PATH, NULL};
exec_builtin(app, (char **)stop_argv, NULL, 0);
sched_unlock();
usb_auto_start_state = UsbAutoStartState::disconnecting;
}
break;
case UsbAutoStartState::disconnecting:
// serial disconnect if unused
serdis_main(0, NULL);
usb_auto_start_state = UsbAutoStartState::disconnected;
break;
if (rescheduled != PX4_OK) {
work_queue(LPWORK, &usb_serial_work, mavlink_usb_check, NULL, USEC2TICK(1000000));
}
}
vbus_present_prev = vbus_present;
if (rescheduled != PX4_OK) {
work_queue(LPWORK, &usb_serial_work, mavlink_usb_check, NULL, USEC2TICK(1000000));
void cdcacm_init(void) {
work_queue(LPWORK, &usb_serial_work, mavlink_usb_check, nullptr, 0);
}
}
void cdcacm_init(void)
{
work_queue(LPWORK, &usb_serial_work, mavlink_usb_check, nullptr, 0);
}
#endif // CONFIG_SYSTEM_CDCACM
@@ -106,10 +106,10 @@ int mcp230XX_register_gpios(uint8_t i2c_bus, uint8_t i2c_addr, int first_minor,
if (!_gpio[i].registered) {
if (dir_mask & mask) {
_gpio[i] = { {GPIO_INPUT_PIN, {}, &mcp_gpio_ops}, mask, false, nullptr};
_gpio[i] = mcp_gpio_dev_s{{GPIO_INPUT_PIN, {}, (uintptr_t) &mcp_gpio_ops}, mask, false, nullptr};
} else {
_gpio[i] = { {GPIO_OUTPUT_PIN, {}, &mcp_gpio_ops}, mask, false, nullptr};
_gpio[i] = mcp_gpio_dev_s{{GPIO_OUTPUT_PIN, {}, (uintptr_t) &mcp_gpio_ops}, mask, false, nullptr};
}
int ret = gpio_pin_register(&_gpio[i].gpio, first_minor + i);
@@ -47,6 +47,8 @@
# define MODULE_NAME "hrt_ioctl"
#endif
#if !defined(CONFIG_BUILD_FLAT)
#define HRT_ENTRY_QUEUE_MAX_SIZE 3
static px4_sem_t g_wait_sem;
static struct hrt_call *next_hrt_entry[HRT_ENTRY_QUEUE_MAX_SIZE];
@@ -170,3 +172,13 @@ hrt_ioctl(unsigned int cmd, unsigned long arg)
return OK;
}
#else /* CONFIG_BUILD_FLAT */
/* For flat builds, hrt functions are called directly, no ioctl needed */
void hrt_ioctl_init(void)
{
/* Nothing to do for flat builds */
}
#endif /* !CONFIG_BUILD_FLAT */
@@ -202,14 +202,16 @@ void print_load_buffer(char *buffer, int buffer_length, print_load_callback_f cb
if (system_load.tasks[i].tcb->pid == 0) {
stack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3);
stack_free = up_check_intstack_remain();
stack_free = (CONFIG_ARCH_INTERRUPTSTACK & ~3) - up_check_intstack(0, 0);
} else {
stack_free = up_check_tcbstack_remain(system_load.tasks[i].tcb);
stack_free = system_load.tasks[i].tcb->adj_stack_size - up_check_tcbstack(system_load.tasks[i].tcb,
system_load.tasks[i].tcb->adj_stack_size);
}
#else
stack_free = up_check_tcbstack_remain(system_load.tasks[i].tcb);
stack_free = system_load.tasks[i].tcb->adj_stack_size - up_check_tcbstack(system_load.tasks[i].tcb,
system_load.tasks[i].tcb->adj_stack_size);
#endif
#if CONFIG_ARCH_BOARD_SIM || !defined(CONFIG_PRIORITY_INHERITANCE)
@@ -223,11 +225,11 @@ void print_load_buffer(char *buffer, int buffer_length, print_load_callback_f cb
uint8_t tcb_sched_priority = system_load.tasks[i].tcb->sched_priority;
unsigned int tcb_num_used_fds = 0; // number of used file descriptors
struct filelist *filelist = &system_load.tasks[i].tcb->group->tg_filelist;
struct fdlist *fdlist = &system_load.tasks[i].tcb->group->tg_fdlist;
for (int fdr = 0; fdr < filelist->fl_rows; fdr++) {
for (int fdr = 0; fdr < fdlist->fl_rows; fdr++) {
for (int fdc = 0; fdc < CONFIG_NFILE_DESCRIPTORS_PER_BLOCK; fdc++) {
if (filelist->fl_files[fdr][fdc].f_inode) {
if (fdlist->fl_fds[fdr][fdc].f_file) {
++tcb_num_used_fds;
}
}
@@ -51,9 +51,9 @@
#include <time.h>
#include <nuttx/fs/fs.h>
#include <crc32.h>
#include <nuttx/crc32.h>
#ifdef CONFIG_BOARD_CRASHDUMP
#ifdef CONFIG_BOARD_CRASHDUMP_CUSTOM
#include <systemlib/hardfault_log.h>
#include "chip.h"
@@ -450,8 +450,8 @@ static int progmem_dump_poll(struct file *filep, struct pollfd *fds,
if (setup) {
fds->revents |= (fds->events & (POLLIN | POLLOUT));
if (fds->revents != 0) {
nxsem_post(fds->sem);
if (fds->revents != 0 && fds->cb != NULL) {
fds->cb(fds);
}
}
+1 -9
View File
@@ -63,19 +63,11 @@
#endif
#if !defined(CONFIG_BUILD_FLAT)
typedef CODE void (*initializer_t)(void);
extern initializer_t _sinit;
extern initializer_t _einit;
extern uint32_t _stext;
extern uint32_t _etext;
static void cxx_initialize(void)
{
initializer_t *initp;
/* Visit each entry in the initialization table */
for (initp = &_sinit; initp != &_einit; initp++) {
for (initializer_t *initp = _sinit; initp != _einit; initp++) {
initializer_t initializer = *initp;
/* Make sure that the address is non-NULL and lies in the text
+8 -4
View File
@@ -51,6 +51,7 @@
#include <inttypes.h>
#include <errno.h>
#include <fcntl.h>
#include <stdbool.h>
#include "systemlib/px4_macros.h"
@@ -59,7 +60,7 @@
#include <nuttx/mtd/mtd.h>
extern "C" {
struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev);
struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev, uint16_t spi_devid);
struct mtd_dev_s *mtd_partition(FAR struct mtd_dev_s *mtd,
off_t firstblock, off_t nblocks);
}
@@ -96,7 +97,7 @@ static int ramtron_attach(mtd_instance_s &instance)
SPI_SELECT(spi, instance.devid, false);
SPI_LOCK(spi, false);
instance.mtd_dev = ramtron_initialize(spi);
instance.mtd_dev = ramtron_initialize(spi, instance.devid);
if (instance.mtd_dev) {
/* abort on first valid result */
@@ -298,7 +299,10 @@ int px4_mtd_config(const px4_mtd_manifest_t *mft_mtd)
return rv;
}
for (uint8_t i = num_instances, num_entry = 0u; i < total_new_instances; ++i, ++num_entry) {
uint8_t i;
uint8_t num_entry;
for (i = num_instances, num_entry = 0u; i < total_new_instances; ++i, ++num_entry) {
instances[i] = new mtd_instance_s;
@@ -414,7 +418,7 @@ memoryout:
/* Now create a character device on the block device */
rv = bchdev_register(blockname, instances[i]->partition_names[part], false);
rv = bchdev_register(blockname, instances[i]->partition_names[part], O_RDWR);
if (rv < 0) {
PX4_ERR("bchdev_register %s failed: %d", instances[i]->partition_names[part], rv);
@@ -41,7 +41,7 @@
#include <px4_arch/io_timer.h>
#include <drivers/drv_dshot.h>
#include <stdio.h>
#include "barriers.h"
#include <arch/barriers.h>
#include "arm_internal.h"
@@ -43,6 +43,7 @@ __BEGIN_DECLS
#define GPIO_OUTPUT_CLEAR GPIO_OUTPUT_ZERO
#include <chip.h>
#include <ssarc_dump.h>
#include <imxrt_lpspi.h>
#include <imxrt_lpi2c.h>
#include <imxrt_iomuxc.h>
@@ -85,7 +86,7 @@ __BEGIN_DECLS
#define px4_savepanic(fileno, context, length) ssarc_dump_savepanic(fileno, context, length)
#if defined(CONFIG_BOARD_CRASHDUMP)
#if defined(CONFIG_BOARD_CRASHDUMP_CUSTOM)
# define HAS_SSARC 1
# define PX4_HF_GETDESC_IOCTL SSARC_DUMP_GETDESC_IOCTL
# define PX4_SSARC_DUMP_BASE IMXRT_SSARC_HP_BASE
@@ -50,9 +50,9 @@
#include <time.h>
#include <nuttx/fs/fs.h>
#include <crc32.h>
#include <nuttx/crc32.h>
#ifdef CONFIG_BOARD_CRASHDUMP
#ifdef CONFIG_BOARD_CRASHDUMP_CUSTOM
#include <systemlib/hardfault_log.h>
#include "chip.h"
@@ -444,8 +444,8 @@ static int ssarc_dump_poll(struct file *filep, struct pollfd *fds,
if (setup) {
fds->revents |= (fds->events & (POLLIN | POLLOUT));
if (fds->revents != 0) {
nxsem_post(fds->sem);
if (fds->revents != 0 && fds->cb != NULL) {
fds->cb(fds);
}
}
@@ -95,7 +95,7 @@ __BEGIN_DECLS
#define px4_savepanic(fileno, context, length) progmem_dump_savepanic(fileno, context, length)
#if defined(CONFIG_ARCH_HAVE_PROGMEM) && defined(CONFIG_BOARD_CRASHDUMP)
#if defined(CONFIG_ARCH_HAVE_PROGMEM) && defined(CONFIG_BOARD_CRASHDUMP_CUSTOM)
# define HAS_PROGMEM 1
#endif
+4
View File
@@ -120,10 +120,14 @@
#ifdef __cplusplus
#include <cstdlib>
#endif
#ifndef CONFIG_NUTTX_USERSPACE
/* We should include cstdlib or stdlib.h but this doesn't
* compile because many C++ files include stdlib.h and would
* need to get changed. */
#pragma GCC poison getenv setenv putenv
#endif
#endif // defined(__PX4_NUTTX)
#endif // PX4_DISABLE_GCC_POISON
+6
View File
@@ -194,6 +194,12 @@ if(NOT "${PX4_BOARD}" MATCHES "px4_io")
else()
add_library(parameters STATIC EXCLUDE_FROM_ALL ${PX4_SOURCE_DIR}/platforms/common/empty.c)
endif()
if(NOT CONFIG_BUILD_FLAT)
target_compile_options(parameters PRIVATE
-fno-use-cxa-atexit
-fno-threadsafe-statics
)
endif()
add_dependencies(parameters prebuild_targets)
if(${PX4_PLATFORM} STREQUAL "nuttx")
+5 -4
View File
@@ -264,7 +264,8 @@ void LoadMon::stack_usage()
if (system_load.tasks[_stack_task_index].valid && (system_load.tasks[_stack_task_index].tcb->pid > 0)) {
stack_free = up_check_tcbstack_remain(system_load.tasks[_stack_task_index].tcb);
stack_free = system_load.tasks[_stack_task_index].tcb->adj_stack_size - up_check_tcbstack(
system_load.tasks[_stack_task_index].tcb, system_load.tasks[_stack_task_index].tcb->adj_stack_size);
strncpy((char *)task_stack_info.task_name, system_load.tasks[_stack_task_index].tcb->name, CONFIG_TASK_NAME_SIZE - 1);
task_stack_info.task_name[CONFIG_TASK_NAME_SIZE - 1] = '\0';
@@ -273,11 +274,11 @@ void LoadMon::stack_usage()
#if CONFIG_NFILE_DESCRIPTORS_PER_BLOCK > 0
unsigned int tcb_num_used_fds = 0; // number of used file descriptors
struct filelist *filelist = &system_load.tasks[_stack_task_index].tcb->group->tg_filelist;
struct fdlist *fdlist = &system_load.tasks[_stack_task_index].tcb->group->tg_fdlist;
for (int fdr = 0; fdr < filelist->fl_rows; fdr++) {
for (int fdr = 0; fdr < fdlist->fl_rows; fdr++) {
for (int fdc = 0; fdc < CONFIG_NFILE_DESCRIPTORS_PER_BLOCK; fdc++) {
if (filelist->fl_files[fdr][fdc].f_inode) {
if (fdlist->fl_fds[fdr][fdc].f_file) {
++tcb_num_used_fds;
}
}
+1 -1
View File
@@ -341,7 +341,7 @@ void TaskWatchdog::capture_and_write_dump()
d.regs[REG_R10], d.regs[REG_R11],
d.regs[REG_R12], d.regs[REG_R13],
d.regs[REG_R14], d.regs[REG_R15]);
#ifdef CONFIG_ARMV7M_USEBASEPRI
#if defined(CONFIG_ARMV7M_USEBASEPRI) || defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__)
dprintf(fd, " xpsr:%08" PRIx32 " basepri:%08" PRIx32 "\n",
d.regs[REG_XPSR], d.regs[REG_BASEPRI]);
#else
+2 -2
View File
@@ -340,7 +340,7 @@ static int write_stack_detail(bool inValid, _stack_s *si, char *sp_name,
tcb.adj_stack_size = si->size;
if (verify_ram_address(sbot, si->size)) {
n = snprintf(buffer, max, " used: 0x%08zx\n", up_check_tcbstack(&tcb));
n = snprintf(buffer, max, " used: 0x%08zx\n", up_check_tcbstack(&tcb, tcb.adj_stack_size));
} else {
n = snprintf(buffer, max, "Invalid Stack! (Corrupted TCB) Stack base: 0x%08" PRIx32 " Stack size: 0x%08"
@@ -459,7 +459,7 @@ static int write_registers(uint32_t regs[], char *buffer, int max, int fd)
return -EIO;
}
#ifdef CONFIG_ARMV7M_USEBASEPRI
#if defined(CONFIG_ARMV7M_USEBASEPRI) || defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__)
n = snprintf(buffer, max, " xpsr:0x%08" PRIx32 " basepri:0x%08" PRIx32 " control:0x%08" PRIx32 "\n",
regs[REG_XPSR], regs[REG_BASEPRI],
getcontrol());