feat: configurable board pwm freq from Kconfig (#24787)

* feat: configurable board pwm freq from Kconfig

* feat: add board_pwm_config to submenu

* fix: define sequence correction

* fix: revert Tools/simulation/gz

* fix: track upstream gz

* fix: track upstream mavlink

* feat: adjustable pwm for multiple board types

* feat: add conditional check for CONFIG_ for correct fallback

* add: spacecraft board with correct BOARD_PWM_FREQ supporting 10Hz actuation rate

* fix: set dependencies for submenu arch chips

* fix: keep only upper arch level

* fix: proper checking - still not showing up for board config

* feat: add hidden kconfig for platforms

* Merge Nuttx config into px4board

Allows to expose nuttx into PX4 if needed

* Kconfig: Include nuttx symbols in updateconfig

Only if applicable i.e. defined in the kconfig

* fix: merged config with previously generated boardconfig

* doc: updated code comment

---------

Co-authored-by: Daniel Agar <daniel@agar.ca>
Co-authored-by: Peter van der Perk <peter.vanderperk@nxp.com>
This commit is contained in:
Pedro Roque 2025-07-23 17:23:13 +02:00 committed by GitHub
parent 8b2c0b4250
commit 6474e5d7c1
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
13 changed files with 102 additions and 9 deletions

View File

@ -206,8 +206,8 @@ source "src/examples/Kconfig"
endmenu
menu "platforms"
depends on PLATFORM_QURT || PLATFORM_POSIX
source "platforms/common/Kconfig"
depends on PLATFORM_QURT || PLATFORM_POSIX || PLATFORM_NUTTX
source "platforms/Kconfig"
endmenu
source "src/lib/*/Kconfig"

View File

@ -101,7 +101,6 @@ def main(kconfig_file, config1, config2):
# load_config() and write_config() returns a message to print.
print(kconf.load_config(config1, replace=False))
print(kconf.load_config(config2, replace=False))
# Modification for PX4 unset all symbols (INT,HEX etc) from 2nd config
f = open(config2, 'r')
@ -113,13 +112,16 @@ def main(kconfig_file, config1, config2):
#pprint.pprint(line)
if match is not None:
sym_name = match.group(1)
kconf.syms[sym_name].unset_value()
try:
kconf.syms[sym_name].unset_value()
if kconf.syms[sym_name].type is BOOL:
for default, cond in kconf.syms[sym_name].orig_defaults:
if(cond.str_value == 'y'):
# Default is y, our diff is unset thus we've set it to no
kconf.syms[sym_name].set_value(0)
if kconf.syms[sym_name].type is BOOL:
for default, cond in kconf.syms[sym_name].orig_defaults:
if(cond.str_value == 'y'):
# Default is y, our diff is unset thus we've set it to no
kconf.syms[sym_name].set_value(0)
except KeyError:
pass
f.close()

View File

@ -41,6 +41,7 @@ import glob
import kconfiglib
import tempfile
import sys
from pathlib import Path
import diffconfig
import merge_config
@ -52,6 +53,14 @@ for name in glob.glob(px4_dir + '/boards/*/*/default.px4board'):
kconf.load_config(name)
print(kconf.write_min_config(name))
board_path = Path(name)
defconfig_path = board_path.parent / "nuttx-config" / "nsh" / "defconfig"
if os.path.exists(defconfig_path):
# Merge NuttX with default config
kconf = merge_config.main(px4_dir + "/Kconfig", name, defconfig_path)
print(kconf.write_min_config(name))
for name in glob.glob(px4_dir + '/boards/*/*/bootloader.px4board'):
kconf = kconfiglib.Kconfig()
kconf.load_config(name)

View File

@ -0,0 +1,21 @@
CONFIG_BOARD_PWM_FREQ=100000
CONFIG_MODULES_AIRSPEED_SELECTOR=n
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_FW_MODE_MANAGER=n
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n
CONFIG_MODULES_FW_RATE_CONTROL=n
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_MC_ATT_CONTROL=n
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
CONFIG_MODULES_MC_POS_CONTROL=n
CONFIG_MODULES_MC_RATE_CONTROL=n
CONFIG_MODULES_VTOL_ATT_CONTROL=n
CONFIG_MODULES_ROVER_ACKERMANN=n
CONFIG_MODULES_ROVER_DIFFERENTIAL=n
CONFIG_MODULES_ROVER_MECANUM=n
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
CONFIG_MODULES_CONTROL_ALLOCATOR=n
CONFIG_MODULES_SPACECRAFT=y

3
platforms/Kconfig Normal file
View File

@ -0,0 +1,3 @@
if PLATFORM_NUTTX
rsource "nuttx/Kconfig"
endif

26
platforms/nuttx/Kconfig Normal file
View File

@ -0,0 +1,26 @@
choice
prompt "NuttX platform"
---help---
This automatically gets set by the NuttX defconfig
config ARCH_CHIP_UNSET
bool "Unset"
config ARCH_CHIP_STM32H7
bool "STM32H7"
config ARCH_CHIP_STM32F7
bool "STM32F7"
config ARCH_CHIP_STM32F4
bool "STM32F4"
config ARCH_CHIP_IMXRT
bool "IMXRT"
config ARCH_CHIP_S32K3XX
bool "S32K3XX"
config ARCH_CHIP_RP2040
bool "RP2040"
endchoice
config BOARD_PWM_FREQ
int "Board default PWM frequency"
default 160000000 if ARCH_CHIP_S32K3XX
default 1000000 if !ARCH_CHIP_S32K3XX
---help---
Board default PWM frequency

View File

@ -108,3 +108,11 @@ foreach(NameAndValue ${ConfigContents})
set(${Name} ${Value} CACHE INTERNAL "NUTTX DEFCONFIG: ${Name}" FORCE)
endif()
endforeach()
# Add CONFIG_ARCH_CHIP to boardconfig by merging
execute_process(
COMMAND ${CMAKE_COMMAND} -E env ${COMMON_KCONFIG_ENV_SETTINGS}
${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/kconfig/merge_config.py Kconfig ${BOARD_CONFIG} ${BOARD_CONFIG} ${PX4_BINARY_DIR}/NuttX/nuttx/.config
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
OUTPUT_VARIABLE DUMMY_RESULTS
)

View File

@ -71,6 +71,10 @@ static int io_timer_handler5(int irq, void *context, void *arg);
static int io_timer_handler6(int irq, void *context, void *arg);
static int io_timer_handler7(int irq, void *context, void *arg);
#ifdef CONFIG_BOARD_PWM_FREQ
#define BOARD_PWM_FREQ CONFIG_BOARD_PWM_FREQ
#endif
#if !defined(BOARD_PWM_FREQ)
#define BOARD_PWM_FREQ 1000000
#endif

View File

@ -79,6 +79,10 @@ static int io_timer_handler7(int irq, void *context, void *arg);
* FTM0 will drive FMU_CH1-4, FTM3 will drive FMU_CH5,6, and
* U_TRI. FTM2 will be used as input capture on U_ECH
*/
#ifdef CONFIG_BOARD_PWM_FREQ
#define BOARD_PWM_FREQ CONFIG_BOARD_PWM_FREQ
#endif
#if !defined(BOARD_PWM_FREQ)
#define BOARD_PWM_FREQ 1000000
#endif

View File

@ -77,6 +77,10 @@ static int io_timer_handler7(int irq, void *context, void *arg);
* All FTM blocks have their clock sources set to the system oscillator
* which should generate an 8 MHz clock.
*/
#ifdef CONFIG_BOARD_PWM_FREQ
#define BOARD_PWM_FREQ CONFIG_BOARD_PWM_FREQ
#endif
#if !defined(BOARD_PWM_FREQ)
#define BOARD_PWM_FREQ 1000000
#endif

View File

@ -79,6 +79,10 @@ static int io_timer_handler7(int irq, void *context, void *arg);
#define BOARD_PWM_PRESCALER 20
#ifdef CONFIG_BOARD_PWM_FREQ
#define BOARD_PWM_FREQ CONFIG_BOARD_PWM_FREQ
#endif
#if !defined(BOARD_PWM_FREQ)
#define BOARD_PWM_FREQ 160000000 / BOARD_PWM_PRESCALER
#endif

View File

@ -65,6 +65,10 @@
// Each timer also has double buffered wrap (rTOP) and level (rCC) registers so the value can
// change while PWM is running.
#ifdef CONFIG_BOARD_PWM_FREQ
#define BOARD_PWM_FREQ CONFIG_BOARD_PWM_FREQ
#endif
#if !defined(BOARD_PWM_FREQ)
#define BOARD_PWM_FREQ 1000000
#endif

View File

@ -91,6 +91,10 @@ static int io_timer_handler7(int irq, void *context, void *arg);
* We also allow for overrides here but all timer register usage need to be
* taken into account
*/
#ifdef CONFIG_BOARD_PWM_FREQ
#define BOARD_PWM_FREQ CONFIG_BOARD_PWM_FREQ
#endif
#if !defined(BOARD_PWM_FREQ)
#define BOARD_PWM_FREQ 1000000
#endif