diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 00000000000..4fcafb90595 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "lib/main/pico-sdk"] + path = lib/main/pico-sdk + url = https://github.com/raspberrypi/pico-sdk.git diff --git a/CMakeLists.txt b/CMakeLists.txt index dc34f9da32b..e0550a3e398 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -92,6 +92,7 @@ endif() include(stm32) include(at32) include(sitl) +include(rp2350) add_subdirectory(src) diff --git a/cmake/cortex-m33.cmake b/cmake/cortex-m33.cmake new file mode 100644 index 00000000000..12acfffbb7d --- /dev/null +++ b/cmake/cortex-m33.cmake @@ -0,0 +1,23 @@ +set(CORTEX_M33_COMMON_OPTIONS + -mthumb + -mcpu=cortex-m33 + -march=armv8-m.main+fp+dsp + -mfloat-abi=hard + -mfpu=fpv5-sp-d16 + -fsingle-precision-constant + -Wdouble-promotion +) + +set(CORTEX_M33_COMPILE_OPTIONS +) + +set(CORTEX_M33_LINK_OPTIONS +) + +set(CORTEX_M33_DEFINITIONS + __FPU_PRESENT=1 + ARM_MATH_CM4 + ARM_MATH_MATRIX_CHECK + ARM_MATH_ROUNDING + UNALIGNED_SUPPORT_DISABLE +) diff --git a/cmake/rp2350.cmake b/cmake/rp2350.cmake new file mode 100644 index 00000000000..0cc1afe2ed0 --- /dev/null +++ b/cmake/rp2350.cmake @@ -0,0 +1,399 @@ +include(cortex-m33) + +set(PICO_SDK_DIR "${MAIN_LIB_DIR}/main/pico-sdk") +set(PICO_SDK_SRC_DIR "${PICO_SDK_DIR}/src") +set(TINYUSB_SRC_DIR "${PICO_SDK_DIR}/lib/tinyusb/src") +set(RP2350_STARTUP_DIR "${MAIN_SRC_DIR}/startup") +set(RP2350_LINKER_DIR "${MAIN_SRC_DIR}/target/link") + +# CMSIS directories (shared with STM32/AT32) +set(RP2350_CMSIS_DIR "${MAIN_LIB_DIR}/main/CMSIS") +set(RP2350_CMSIS_INCLUDE_DIR "${RP2350_CMSIS_DIR}/Core/Include") +set(RP2350_CMSIS_DSP_DIR "${RP2350_CMSIS_DIR}/DSP") +set(RP2350_CMSIS_DSP_INCLUDE_DIR "${RP2350_CMSIS_DSP_DIR}/Include") + +# NOTE: CMSIS DSP sources are NOT compiled for RP2350. +# The bundled CMSIS DSP (arm_math.h) predates ARMv8-M and conflicts with +# the newer CMSIS Core headers. DSP functions are stubbed in system_rp2350.c. +# The DSP include dir is still needed for arm_math.h type definitions. + +# Sources to exclude from COMMON_SRC (same as SITL + additional STM32-specific) +main_sources(RP2350_COMMON_SRC_EXCLUDES + build/atomic.h + drivers/system.c + drivers/time.c + drivers/timer.c + drivers/rcc.c + drivers/persistent.c + drivers/io.c + drivers/accgyro/accgyro_mpu.c + drivers/display_ug2864hsweg01.c + io/displayport_oled.c + # LED strip: replaced by light_ws2811strip_rp2350.c (PIO2+DMA, no timer/DMA abstraction) + drivers/light_ws2811strip.c + # I2C: replaced by bus_i2c_rp2350.c (Pico SDK blocking API; HAL version needs STM32 HAL) + drivers/bus_i2c_hal.c + # SPI: replaced by bus_spi_rp2350.c (Pico SDK blocking API; HAL/LL version needs STM32 HAL) + drivers/bus_spi_hal_ll.c +) + +# INAV platform-specific sources +main_sources(RP2350_SRC + config/config_streamer_rp2350.c + drivers/io_rp2350.c + drivers/system_rp2350.c + drivers/timer_rp2350.c + drivers/serial_usb_vcp_rp2350.c + drivers/serial_uart_rp2350.c + drivers/uart_pio_rp2350.c + drivers/pwm_output_rp2350.c + drivers/adc_rp2350.c + drivers/light_ws2811strip_rp2350.c + drivers/bus_i2c_rp2350.c + drivers/bus_spi_rp2350.c + drivers/persistent_rp2350.c +) + +# --- Pico SDK sources --- +set(PICO_SDK_SOURCES + # Startup (SDK crt0 replaces our custom startup_rp2350.s) + ${PICO_SDK_SRC_DIR}/rp2_common/pico_crt0/crt0.S + + # Platform & runtime + ${PICO_SDK_SRC_DIR}/rp2350/pico_platform/platform.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_platform_panic/panic.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_runtime/runtime.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_runtime_init/runtime_init.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_runtime_init/runtime_init_clocks.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_runtime_init/runtime_init_stack_guard.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_standard_binary_info/standard_binary_info.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_bootrom/bootrom.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_bootrom/bootrom_lock.c + + # Hardware drivers + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_gpio/gpio.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_clocks/clocks.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_pll/pll.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_xosc/xosc.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_ticks/ticks.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_timer/timer.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_watchdog/watchdog.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_irq/irq.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_irq/irq_handler_chain.S + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_sync/sync.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_sync_spin_lock/sync_spin_lock.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_vreg/vreg.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_xip_cache/xip_cache.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_uart/uart.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_pio/pio.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_adc/adc.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_dma/dma.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_i2c/i2c.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_spi/spi.c + + # Sync / time / util + ${PICO_SDK_SRC_DIR}/common/hardware_claim/claim.c + ${PICO_SDK_SRC_DIR}/common/pico_sync/mutex.c + ${PICO_SDK_SRC_DIR}/common/pico_sync/lock_core.c + ${PICO_SDK_SRC_DIR}/common/pico_sync/critical_section.c + ${PICO_SDK_SRC_DIR}/common/pico_sync/sem.c + ${PICO_SDK_SRC_DIR}/common/pico_time/time.c + ${PICO_SDK_SRC_DIR}/common/pico_time/timeout_helper.c + ${PICO_SDK_SRC_DIR}/common/pico_util/datetime.c + ${PICO_SDK_SRC_DIR}/common/pico_util/pheap.c + ${PICO_SDK_SRC_DIR}/common/pico_util/queue.c + + # C library interface / stdlib / atomic + # NOTE: pico_malloc is excluded — it uses --wrap=malloc which conflicts with + # INAV's existing allocation. newlib's malloc is used directly instead. + ${PICO_SDK_SRC_DIR}/rp2_common/pico_clib_interface/newlib_interface.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_stdlib/stdlib.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_atomic/atomic.c + + # stdio / printf / stdio_usb + ${PICO_SDK_SRC_DIR}/rp2_common/pico_stdio/stdio.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_printf/printf.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_stdio_usb/stdio_usb.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_stdio_usb/stdio_usb_descriptors.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_stdio_usb/reset_interface.c + + # Unique ID + ${PICO_SDK_SRC_DIR}/rp2_common/pico_unique_id/unique_id.c + + # Divider (compiler builtins) + ${PICO_SDK_SRC_DIR}/rp2_common/pico_divider/divider_compiler.c + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_divider/divider.c + + # Flash (needed for unique_id) + ${PICO_SDK_SRC_DIR}/rp2_common/hardware_flash/flash.c + ${PICO_SDK_SRC_DIR}/rp2_common/pico_flash/flash.c +) + +# --- TinyUSB sources --- +set(TINYUSB_SOURCES + ${TINYUSB_SRC_DIR}/tusb.c + ${TINYUSB_SRC_DIR}/common/tusb_fifo.c + ${TINYUSB_SRC_DIR}/device/usbd.c + ${TINYUSB_SRC_DIR}/device/usbd_control.c + ${TINYUSB_SRC_DIR}/class/cdc/cdc_device.c + ${TINYUSB_SRC_DIR}/portable/raspberrypi/rp2040/dcd_rp2040.c + ${TINYUSB_SRC_DIR}/portable/raspberrypi/rp2040/rp2040_usb.c +) + +# --- Pico SDK include directories --- +set(PICO_SDK_INCLUDE_DIRS + # Common headers + "${PICO_SDK_SRC_DIR}/common/pico_base_headers/include" + "${PICO_SDK_SRC_DIR}/common/pico_binary_info/include" + "${PICO_SDK_SRC_DIR}/common/pico_bit_ops_headers/include" + "${PICO_SDK_SRC_DIR}/common/pico_stdlib_headers/include" + "${PICO_SDK_SRC_DIR}/common/pico_sync/include" + "${PICO_SDK_SRC_DIR}/common/pico_time/include" + "${PICO_SDK_SRC_DIR}/common/pico_util/include" + "${PICO_SDK_SRC_DIR}/common/pico_usb_reset_interface_headers/include" + "${PICO_SDK_SRC_DIR}/common/hardware_claim/include" + "${PICO_SDK_SRC_DIR}/common/boot_picobin_headers/include" + "${PICO_SDK_SRC_DIR}/common/boot_picoboot_headers/include" + "${PICO_SDK_SRC_DIR}/common/boot_uf2_headers/include" + "${PICO_SDK_SRC_DIR}/common/pico_divider_headers/include" + + # RP2350-specific headers + "${PICO_SDK_SRC_DIR}/rp2350/hardware_regs/include" + "${PICO_SDK_SRC_DIR}/rp2350/hardware_structs/include" + "${PICO_SDK_SRC_DIR}/rp2350/pico_platform/include" + "${PICO_SDK_SRC_DIR}/rp2350/boot_stage2/include" + + # rp2_common hardware + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_base/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_gpio/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_clocks/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_irq/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_pll/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_sync/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_sync_spin_lock/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_ticks/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_timer/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_uart/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_resets/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_watchdog/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_xosc/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_vreg/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_xip_cache/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_divider/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_flash/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_boot_lock/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_exception/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_dma/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_spi/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_i2c/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_adc/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_pwm/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_pio/include" + "${PICO_SDK_SRC_DIR}/rp2_common/hardware_powman/include" + + # rp2_common pico libraries + "${PICO_SDK_SRC_DIR}/rp2_common/pico_platform_compiler/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_platform_panic/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_platform_sections/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_stdio/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_stdio_usb/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_printf/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_runtime/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_runtime_init/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_bootrom/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_unique_id/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_stdlib/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_clib_interface/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_malloc/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_atomic/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_flash/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_float/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_double/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_int64_ops/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_mem_ops/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_multicore/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_rand/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_standard_binary_info/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_aon_timer/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_time_adapter/include" + "${PICO_SDK_SRC_DIR}/rp2_common/boot_bootrom_headers/include" + "${PICO_SDK_SRC_DIR}/rp2_common/pico_divider/include" + + # CMSIS + "${PICO_SDK_SRC_DIR}/rp2_common/cmsis/include" + + # TinyUSB + "${TINYUSB_SRC_DIR}" + "${PICO_SDK_SRC_DIR}/rp2_common/tinyusb/include" +) + +set(RP2350_DEFINITIONS + RP2350 + PICO_RP2350=1 + PICO_RP2350A=1 + PICO_32BIT=1 + # Do NOT define PICO_RP2040 at all — even PICO_RP2040=0 counts as "defined" + # for #ifdef/#elif defined() checks in the Pico SDK assembly (embedded_start_block.inc.S), + # which would cause the IMAGE_DEF to declare RP2040 chip type instead of RP2350. + PICO_CONFIG_HEADER=pico_sdk_config.h + PICO_NO_FPGA_CHECK=1 + PICO_FLASH_SIZE_BYTES=4194304 + ${CORTEX_M33_DEFINITIONS} +) + +set(RP2350_COMPILE_OPTIONS + ${CORTEX_M33_COMMON_OPTIONS} + -ffunction-sections + -fdata-sections + -fno-common + -fno-builtin-memcpy + -funsigned-char +) + +set(RP2350_LINK_LIBRARIES + -lm + -lc + -lnosys +) + +set(RP2350_LINK_OPTIONS + ${CORTEX_M33_COMMON_OPTIONS} + -nostartfiles + --specs=nano.specs + -static + -Wl,-gc-sections + -Wl,-L${RP2350_LINKER_DIR} + -Wl,--cref + -Wl,--no-wchar-size-warning + -Wl,--print-memory-usage +) + +set(RP2350_INCLUDE_DIRS + "${RP2350_CMSIS_INCLUDE_DIR}" + "${RP2350_CMSIS_DSP_INCLUDE_DIR}" + "${MAIN_SRC_DIR}/target" + ${PICO_SDK_INCLUDE_DIRS} +) + +function(target_rp2350 name) + if(NOT arm-none-eabi STREQUAL TOOLCHAIN) + return() + endif() + + exclude(COMMON_SRC "${RP2350_COMMON_SRC_EXCLUDES}") + + set(target_sources) + # Pico SDK startup (crt0.S) and SDK sources + list(APPEND target_sources ${PICO_SDK_SOURCES}) + # TinyUSB sources + list(APPEND target_sources ${TINYUSB_SOURCES}) + # Boot2 stage 2 bootloader + list(APPEND target_sources + ${RP2350_STARTUP_DIR}/boot2_rp2350.S + ) + # INAV platform sources + list(APPEND target_sources ${RP2350_SRC}) + # Target directory sources + file(GLOB target_c_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.c") + file(GLOB target_h_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.h") + list(APPEND target_sources ${target_c_sources} ${target_h_sources}) + + set(target_definitions ${RP2350_DEFINITIONS} ${COMMON_COMPILE_DEFINITIONS}) + + math(EXPR hse_value "12 * 1000000") + list(APPEND target_definitions "HSE_VALUE=${hse_value}") + + if (MSP_UART) + list(APPEND target_definitions "MSP_UART=${MSP_UART}") + endif() + + string(TOLOWER ${PROJECT_NAME} lowercase_project_name) + set(binary_name ${lowercase_project_name}_${FIRMWARE_VERSION}_${name}) + if(DEFINED BUILD_SUFFIX AND NOT "" STREQUAL "${BUILD_SUFFIX}") + set(binary_name "${binary_name}_${BUILD_SUFFIX}") + endif() + + set(exe_target ${name}.elf) + add_executable(${exe_target}) + target_sources(${exe_target} PRIVATE ${target_sources} ${COMMON_SRC}) + target_include_directories(${exe_target} PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR} + ${RP2350_INCLUDE_DIRS} + ) + target_compile_definitions(${exe_target} PRIVATE ${target_definitions}) + target_compile_options(${exe_target} PRIVATE ${RP2350_COMPILE_OPTIONS}) + + # Pico SDK requires C11 (static_assert). Override INAV's global C99 setting. + set_target_properties(${exe_target} PROPERTIES C_STANDARD 11) + + if(WARNINGS_AS_ERRORS) + target_compile_options(${exe_target} PRIVATE -Werror) + endif() + + target_link_libraries(${exe_target} PRIVATE ${RP2350_LINK_LIBRARIES}) + target_link_options(${exe_target} PRIVATE ${RP2350_LINK_OPTIONS}) + + # Linker script + set(script_path ${RP2350_LINKER_DIR}/rp2350_flash.ld) + if(NOT EXISTS ${script_path}) + message(FATAL_ERROR "linker script ${script_path} doesn't exist") + endif() + set_target_properties(${exe_target} PROPERTIES LINK_DEPENDS ${script_path}) + target_link_options(${exe_target} PRIVATE -T${script_path}) + + # Map file + if(CMAKE_VERSION VERSION_LESS 3.15) + set(map "$.map") + else() + set(map "$/$.map") + endif() + target_link_options(${exe_target} PRIVATE "-Wl,-Map,${map}") + + # Generate .hex output + set(hex_filename ${CMAKE_BINARY_DIR}/${binary_name}.hex) + add_custom_target(${name} ALL + cmake -E env PATH="$ENV{PATH}" + ${CMAKE_OBJCOPY} -Oihex $ ${hex_filename} + BYPRODUCTS ${hex_filename} + ) + + # Generate .bin output + set(bin_filename ${CMAKE_BINARY_DIR}/${binary_name}.bin) + add_custom_command(TARGET ${name} POST_BUILD + COMMAND ${CMAKE_OBJCOPY} -Obinary $ ${bin_filename} + BYPRODUCTS ${bin_filename} + COMMENT "Generating ${binary_name}.bin" + ) + + # Generate .uf2 output (for BOOTSEL drag-and-drop flashing) + # Use picotool which correctly handles the RP2350 IMAGE_DEF metadata block. + set(uf2_filename ${CMAKE_BINARY_DIR}/${binary_name}.uf2) + add_custom_command(TARGET ${name} POST_BUILD + COMMAND picotool uf2 convert + $ + ${uf2_filename} + --family rp2350-arm-s + BYPRODUCTS ${uf2_filename} + COMMENT "Generating ${binary_name}.uf2 via picotool" + ) + + setup_firmware_target(${exe_target} ${name} ${ARGN}) + + # clean_ + set(generator_cmd "") + if (CMAKE_GENERATOR STREQUAL "Unix Makefiles") + set(generator_cmd "make") + elseif(CMAKE_GENERATOR STREQUAL "Ninja") + set(generator_cmd "ninja") + endif() + if (NOT generator_cmd STREQUAL "") + set(clean_target "clean_${name}") + add_custom_target(${clean_target} + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + COMMAND ${generator_cmd} clean + COMMENT "Removing intermediate files for ${name}") + set_property(TARGET ${clean_target} PROPERTY + EXCLUDE_FROM_ALL 1 + EXCLUDE_FROM_DEFAULT_BUILD 1) + endif() +endfunction() diff --git a/lib/main/pico-sdk b/lib/main/pico-sdk new file mode 160000 index 00000000000..95ea6acad13 --- /dev/null +++ b/lib/main/pico-sdk @@ -0,0 +1 @@ +Subproject commit 95ea6acad131124694cda1c162c52cd30e0aece0 diff --git a/src/main/common/filter.c b/src/main/common/filter.c index 5fd72965d85..2e9e4574e71 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -44,7 +44,7 @@ float nullFilterApply4(void *filter, float input, float f_cut, float dt) // PT1 Low Pass filter -static float pt1ComputeRC(const float f_cut) +static float FAST_CODE pt1ComputeRC(const float f_cut) { return 1.0f / (2.0f * M_PIf * f_cut); } diff --git a/src/main/common/maths.c b/src/main/common/maths.c index 993634d902d..5e1587bbd34 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -67,7 +67,7 @@ float cos_approx(float x) // http://http.developer.nvidia.com/Cg/atan2.html (not working correctly!) // Poly coefficients by @ledvinap (https://github.com/cleanflight/cleanflight/pull/1107) // Max absolute error 0,000027 degree -float atan2_approx(float y, float x) +float RP2350_FAST_CODE atan2_approx(float y, float x) { #define atanPolyCoef1 3.14551665884836e-07f #define atanPolyCoef2 0.99997356613987f @@ -94,7 +94,7 @@ float atan2_approx(float y, float x) // Handbook of Mathematical Functions // M. Abramowitz and I.A. Stegun, Ed. // Absolute error <= 6.7e-5 -float acos_approx(float x) +float RP2350_FAST_CODE acos_approx(float x) { float xa = fabsf(x); float result = fast_fsqrtf(1.0f - xa) * (1.5707288f + xa * (-0.2121144f + xa * (0.0742610f + (-0.0187293f * xa)))); @@ -165,7 +165,7 @@ int32_t applyDeadbandRescaled(int32_t value, int32_t deadband, int32_t min, int3 return value; } -int32_t constrain(int32_t amt, int32_t low, int32_t high) +int32_t FAST_CODE constrain(int32_t amt, int32_t low, int32_t high) { if (amt < low) return low; @@ -175,7 +175,7 @@ int32_t constrain(int32_t amt, int32_t low, int32_t high) return amt; } -float constrainf(float amt, float low, float high) +float FAST_CODE constrainf(float amt, float low, float high) { if (amt < low) return low; @@ -225,7 +225,7 @@ int scaleRange(int x, int srcMin, int srcMax, int destMin, int destMax) { return ((a / b) + destMin); } -float scaleRangef(float x, float srcMin, float srcMax, float destMin, float destMax) { +float FAST_CODE scaleRangef(float x, float srcMin, float srcMax, float destMin, float destMax) { float a = (destMax - destMin) * (x - srcMin); float b = srcMax - srcMin; return ((a / b) + destMin); diff --git a/src/main/config/config_streamer_ram.c b/src/main/config/config_streamer_ram.c index 420e2a0e6ce..555f60d0fe2 100644 --- a/src/main/config/config_streamer_ram.c +++ b/src/main/config/config_streamer_ram.c @@ -17,6 +17,7 @@ #include #include "platform.h" +#include "common/utils.h" #include "drivers/system.h" #include "config/config_streamer.h" diff --git a/src/main/config/config_streamer_rp2350.c b/src/main/config/config_streamer_rp2350.c new file mode 100644 index 00000000000..53f9e595301 --- /dev/null +++ b/src/main/config/config_streamer_rp2350.c @@ -0,0 +1,166 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * RP2350 flash-based config storage — Milestone 4 (missing piece) + * + * INAV config is stored in the FLASH_CONFIG region defined by the linker + * script (rp2350_flash.ld): + * FLASH_CONFIG: 0x103F0000, 64 KB + * + * Flash is XIP-mapped starting at XIP_BASE (0x10000000), so the region is + * directly readable as normal memory. Writes use the Pico SDK flash APIs: + * flash_range_erase() -- erases in 4 KB (FLASH_SECTOR_SIZE) chunks + * flash_range_program() -- programs in 256-byte (FLASH_PAGE_SIZE) chunks + * + * Both APIs take an offset from the start of flash (not the XIP address) and + * MUST be called with interrupts disabled. Multicore safety (M12) is deferred; + * for now disabling interrupts is sufficient because core1 is not started. + * + * The config_streamer interface calls config_streamer_impl_write_word() once + * per CONFIG_STREAMER_BUFFER_SIZE (4 bytes) -- smaller than the 256-byte flash + * page. We accumulate writes in a static page buffer and flush to flash when + * the page is full. The final partial page is flushed in + * config_streamer_impl_lock(), which is called by config_streamer_finish(). + */ + +#include +#include "platform.h" +#include "config/config_streamer.h" + +#if defined(RP2350) && defined(CONFIG_IN_FLASH) + +#include "hardware/flash.h" +#include "hardware/sync.h" + +/* + * Use the SDK's own canonical macros (defined in hardware/flash.h): + * XIP_BASE = 0x10000000 (flash start in XIP address space) + * FLASH_PAGE_SIZE = 256 (minimum program unit) + * FLASH_SECTOR_SIZE = 4096 (minimum erase unit) + */ + +/* One-page write buffer. Filled word-by-word; programmed to flash when full. + * Initialised to 0xFF (erased state) so partial last pages are padded cleanly. */ +static uint8_t pageBuffer[FLASH_PAGE_SIZE]; +static uint32_t pageBufferBase; /* flash offset (from XIP_BASE) of pageBuffer[0] */ +static uint32_t pageBufferUsed; /* bytes filled so far in pageBuffer */ + +/* --- Helper: program the current page buffer to flash ---------------------- */ + +static void flushPageBuffer(void) +{ + if (pageBufferUsed == 0) { + return; + } + /* Pad any unfilled tail with 0xFF (erased value) before programming */ + if (pageBufferUsed < FLASH_PAGE_SIZE) { + memset(pageBuffer + pageBufferUsed, 0xFF, + FLASH_PAGE_SIZE - pageBufferUsed); + } + + uint32_t ints = save_and_disable_interrupts(); + flash_range_program(pageBufferBase, pageBuffer, FLASH_PAGE_SIZE); + restore_interrupts(ints); + + /* Advance to next page and reset buffer */ + pageBufferBase += FLASH_PAGE_SIZE; + memset(pageBuffer, 0xFF, FLASH_PAGE_SIZE); + pageBufferUsed = 0; +} + +/* --- config_streamer interface ---------------------------------------------- */ + +/* + * Called once at the start of a save operation. + * + * Erases the entire config region up front rather than sector-by-sector as + * each boundary is crossed (as STM32 drivers do). The eager-erase strategy + * ensures the XIP cache sees a fully erased region before any programming + * begins, avoiding stale cache lines from a previous partial write. + * + * Interrupts are disabled for the duration of the erase. + * + * TODO M12 (multicore): replace with flash_safe_execute() when core1 is active. + */ +void config_streamer_impl_unlock(void) +{ + uint32_t flashOffset = (uint32_t)(uintptr_t)&__config_start - XIP_BASE; + uint32_t eraseSize = (uint32_t)(uintptr_t)&__config_end + - (uint32_t)(uintptr_t)&__config_start; + + uint32_t ints = save_and_disable_interrupts(); + flash_range_erase(flashOffset, eraseSize); + restore_interrupts(ints); + + /* Initialise page buffer at the start of the config region */ + memset(pageBuffer, 0xFF, FLASH_PAGE_SIZE); + pageBufferBase = flashOffset; + pageBufferUsed = 0; +} + +/* + * Called once at the end of a save operation (via config_streamer_finish). + * Flushes any partial page that has not yet been programmed. + */ +void config_streamer_impl_lock(void) +{ + flushPageBuffer(); +} + +/* + * Called once per CONFIG_STREAMER_BUFFER_SIZE (4 bytes) by the generic streamer. + * Accumulates words into pageBuffer; programs a flash page when it fills up. + * + * c->address is the XIP-mapped flash address of the word being written. + */ +int config_streamer_impl_write_word(config_streamer_t *c, + config_streamer_buffer_align_type_t *buffer) +{ + if (c->err != 0) { + return c->err; + } + + uint32_t flashOffset = (uint32_t)(uintptr_t)c->address - XIP_BASE; + uint32_t offsetInPage = flashOffset - pageBufferBase; + + /* Guard against a caller bug or unexpected rewind of c->address */ + if (offsetInPage >= FLASH_PAGE_SIZE) { + c->err = -1; + return c->err; + } + + memcpy(pageBuffer + offsetInPage, buffer, CONFIG_STREAMER_BUFFER_SIZE); + pageBufferUsed = offsetInPage + CONFIG_STREAMER_BUFFER_SIZE; + + /* Program and advance when we have a complete page */ + if (pageBufferUsed == FLASH_PAGE_SIZE) { + flushPageBuffer(); + } + + c->address += CONFIG_STREAMER_BUFFER_SIZE; + return 0; +} + +#endif /* RP2350 && CONFIG_IN_FLASH */ diff --git a/src/main/drivers/accgyro/accgyro.c b/src/main/drivers/accgyro/accgyro.c index 4182e760b5b..9382fe17bf8 100644 --- a/src/main/drivers/accgyro/accgyro.c +++ b/src/main/drivers/accgyro/accgyro.c @@ -22,7 +22,7 @@ #include "platform.h" -#if !defined(SITL_BUILD) +#if !defined(SITL_BUILD) && !defined(RP2350) #include "build/atomic.h" #endif diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index 679723e0a83..c4ad8a2d972 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -26,7 +26,7 @@ #include "common/utils.h" #include "drivers/adc.h" -#if defined(USE_ADC) && !defined(SITL_BUILD) +#if defined(USE_ADC) && !defined(SITL_BUILD) && !defined(RP2350) #include "drivers/io.h" #include "drivers/adc_impl.h" @@ -242,6 +242,9 @@ uint16_t adcGetChannel(uint8_t channel) #else // USE_ADC +/* RP2350 provides its own full implementation in adc_rp2350.c */ +#if !defined(RP2350) + bool adcIsFunctionAssigned(uint8_t function) { UNUSED(function); @@ -258,4 +261,6 @@ uint16_t adcGetChannel(uint8_t channel) UNUSED(channel); return 0; } -#endif + +#endif /* !RP2350 */ +#endif /* USE_ADC */ diff --git a/src/main/drivers/adc_rp2350.c b/src/main/drivers/adc_rp2350.c new file mode 100644 index 00000000000..ec2c0401621 --- /dev/null +++ b/src/main/drivers/adc_rp2350.c @@ -0,0 +1,183 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * RP2350 ADC driver — round-robin DMA ring buffer — Milestone 8 + * + * RP2350A ADC channels (GPIO → ADC ch → INAV adcChannel_e): + * GPIO26 → ADC0 → ADC_CHN_1 (VBAT) + * GPIO27 → ADC1 → ADC_CHN_2 (CURRENT) + * GPIO28 → ADC2 → ADC_CHN_3 (RSSI) + * GPIO29 → ADC3 → not assigned (padding / VSYS on Pico 2) + * + * The RP2350 DMA ring buffer must be a power-of-2 size. With 3 real + * channels we pad to 4 by adding ADC3 (GPIO29) so the buffer is + * 4 × 2 bytes = 8 bytes = 2^3. GPIO29 is the on-board VSYS/3 divider + * on Pico 2 and causes no harm as an unassigned ADC slot. + * + * ADC sample rate: clkdiv=65535 → ~10 samples/sec per channel. + * Battery voltage changes are slow — this rate is more than adequate. + * + * adcGetChannel() is always non-blocking: it reads the DMA-cached buffer. + */ + +#include "platform.h" + +#if defined(USE_ADC) && defined(RP2350) + +#include +#include +#include + +#include "common/utils.h" +#include "drivers/adc.h" + +#include "hardware/adc.h" +#include "hardware/dma.h" + +/* ── Channel layout ─────────────────────────────────────────────────────── */ + +/* Number of ADC channels sampled in round-robin (must be power-of-2) */ +#define ADC_RR_COUNT 4u /* ch0=GPIO26, ch1=GPIO27, ch2=GPIO28, ch3=GPIO29 */ + +/* GPIO pin of the first ADC channel (ADC0 = GPIO26 on RP2350A) */ +#define ADC_BASE_GPIO 26u + +/* DMA ring size bits: log2(ADC_RR_COUNT × sizeof(uint16_t)) = log2(8) = 3 */ +#define ADC_RING_BITS 3u + +/* DMA result buffer — one slot per round-robin channel, filled continuously. + * Must be volatile (DMA writes behind the compiler's back) and aligned to a + * power-of-2 boundary ≥ buffer size for the DMA ring mode (2^ADC_RING_BITS = 8 bytes). */ +static volatile uint16_t adcDmaBuf[ADC_RR_COUNT] __attribute__((aligned(1u << ADC_RING_BITS))); + +static adcChannel_e adcFunctionMap[ADC_FUNCTION_COUNT]; + +static bool adcReady = false; + +/* ── Helper ──────────────────────────────────────────────────────────────── */ + +/* + * Convert an adcChannel_e (ADC_CHN_1..ADC_CHN_4) to a 0-based RP2350 ADC + * channel index. Returns -1 for ADC_CHN_NONE or out-of-range values. + */ +static int chnToRp2350Ch(adcChannel_e chn) +{ + if (chn < ADC_CHN_1 || chn > ADC_CHN_4) { + return -1; + } + return (int)(chn - ADC_CHN_1); /* ADC_CHN_1 → 0, ADC_CHN_2 → 1, … */ +} + +/* ── INAV ADC API ────────────────────────────────────────────────────────── */ + +bool adcIsFunctionAssigned(uint8_t function) +{ + if (function >= ADC_FUNCTION_COUNT) { + return false; + } + return adcFunctionMap[function] != ADC_CHN_NONE; +} + +int adcGetFunctionChannelAllocation(uint8_t function) +{ + if (function >= ADC_FUNCTION_COUNT) { + return ADC_CHN_NONE; + } + return (int)adcFunctionMap[function]; +} + +uint16_t adcGetChannel(uint8_t function) +{ + if (!adcReady || function >= ADC_FUNCTION_COUNT) { + return 0; + } + int ch = chnToRp2350Ch(adcFunctionMap[function]); + if (ch < 0 || (uint)ch >= ADC_RR_COUNT) { + return 0; + } + return adcDmaBuf[ch]; +} + +void adcInit(drv_adc_config_t *init) +{ + for (int i = 0; i < ADC_FUNCTION_COUNT; i++) { + adcFunctionMap[i] = (adcChannel_e)init->adcFunctionChannel[i]; + } + + adc_init(); + + /* Enable all four ADC input GPIOs (ch0–ch3 = GPIO26–29) */ + for (uint i = 0; i < ADC_RR_COUNT; i++) { + adc_gpio_init(ADC_BASE_GPIO + i); + } + + /* Round-robin: channels 0–3 (bit mask 0x0F) */ + adc_set_round_robin(0x0Fu); + + /* Very slow: ~10 samples/sec per channel — ADC clkdiv max value */ + adc_set_clkdiv(65535.0f); + + /* + * Enable the ADC FIFO and its DREQ signal so DMA can pace transfers. + * Parameters: en=true, dreq_en=true, dreq_thresh=1, err_in_fifo=false, + * byte_shift=false (keep full 12-bit result in 16-bit entry). + * Without this call, DREQ_ADC is never asserted and DMA stalls immediately. + */ + adc_fifo_setup(true, true, 1, false, false); + + /* ── DMA ring buffer setup ────────────────────────────────────────── */ + + int dma_ch = dma_claim_unused_channel(false); + if (dma_ch < 0) { + /* No free DMA channel — ADC driver unavailable */ + return; + } + + dma_channel_config cfg = dma_channel_get_default_config((uint)dma_ch); + channel_config_set_transfer_data_size(&cfg, DMA_SIZE_16); + channel_config_set_read_increment(&cfg, false); /* always read adc_hw->fifo */ + channel_config_set_write_increment(&cfg, true); /* advance through buffer */ + channel_config_set_dreq(&cfg, DREQ_ADC); + + /* + * Ring mode: write pointer wraps at a 2^ADC_RING_BITS byte boundary. + * adcDmaBuf is 8 bytes (ADC_RR_COUNT × 2), so ring_size_bits=3. + * transfer_count=0xFFFFFFFF gives effectively endless transfers. + */ + channel_config_set_ring(&cfg, true, ADC_RING_BITS); + + dma_channel_configure( + (uint)dma_ch, + &cfg, + (void *)adcDmaBuf, /* write destination (cast away volatile for SDK) */ + &adc_hw->fifo, /* read source: ADC FIFO output register (not result) */ + 0xFFFFFFFFu, /* endless — wraps in ring mode */ + true); /* start immediately */ + + adc_run(true); + adcReady = true; +} + +#endif /* USE_ADC && RP2350 */ diff --git a/src/main/drivers/bus_i2c_rp2350.c b/src/main/drivers/bus_i2c_rp2350.c new file mode 100644 index 00000000000..cc1d5240c2d --- /dev/null +++ b/src/main/drivers/bus_i2c_rp2350.c @@ -0,0 +1,234 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * RP2350 I2C driver — blocking, Pico SDK hardware_i2c. + * + * Implements the INAV bus_i2c.h interface using the Pico SDK blocking API. + * No interrupts are used; all transfers complete before returning. + * + * Hardware mapping (Option C pin plan): + * INAV I2CDEV_1 → RP2350 i2c1 → GP18 (SDA = PB2) / GP19 (SCL = PB3) + * + * The allowRawAccess parameter: + * When reg == 0xFF and allowRawAccess == true, the register sub-address byte + * is omitted, allowing raw I2C transactions (used by some mag drivers). + * + * Reference: Pico SDK hardware_i2c API + * INAV src/main/drivers/bus_i2c_hal.c (STM32 reference) + */ + +#include +#include +#include + +#include "platform.h" + +#ifdef USE_I2C + +#include "drivers/bus_i2c.h" +#include "drivers/io.h" +#include "drivers/io_def.h" + +#include "hardware/gpio.h" +#include "hardware/i2c.h" + +#define RP2350_I2C_TIMEOUT_US 10000U /* 10 ms — generous for 100–800 kHz */ + +/* + * Maximum data payload for a register-prefixed write. + * Sensor registers never exceed this in INAV's driver set. + */ +#define I2C_MAX_WRITE_LEN 64U + +/* INAV I2CSpeed enum → baud rate (Hz). + * Enum values are non-sequential; index by enum directly. */ +static const uint32_t speedToBaud[] = { + [I2C_SPEED_400KHZ] = 400000U, + [I2C_SPEED_800KHZ] = 800000U, + [I2C_SPEED_100KHZ] = 100000U, + [I2C_SPEED_200KHZ] = 200000U, +}; +#define SPEED_TABLE_COUNT (sizeof(speedToBaud) / sizeof(speedToBaud[0])) + +static uint32_t i2cBaudrate = 400000U; +static uint16_t i2cErrorCount = 0; + +typedef struct { + i2c_inst_t *hw; + bool initialised; +} rp2350_i2c_state_t; + +static rp2350_i2c_state_t i2cState[I2CDEV_COUNT]; + +/* + * Map a GPIO number to i2c0 or i2c1. + * RP2350 I2C mux pattern: (gpio / 2) is odd → i2c1, even → i2c0. + * GP0/1 → i2c0, GP2/3 → i2c1, GP4/5 → i2c0, GP6/7 → i2c1 + * GP8/9 → i2c0, GP10/11 → i2c1, GP12/13 → i2c0, GP14/15 → i2c1 + * GP16/17 → i2c0, GP18/19 → i2c1, GP20/21 → i2c0, GP22/23 → i2c1 + */ +static i2c_inst_t *gpioToI2cHw(uint gpio) +{ + return ((gpio / 2u) & 1u) ? i2c1 : i2c0; +} + +static inline uint ioTagToGpio(ioTag_t tag) +{ + return (uint)(DEFIO_TAG_GPIOID(tag) * 16u + DEFIO_TAG_PIN(tag)); +} + +/* ─── Public API ──────────────────────────────────────────────────────────── */ + +void i2cSetSpeed(uint8_t speed) +{ + if ((size_t)speed < SPEED_TABLE_COUNT && speedToBaud[speed] != 0) { + i2cBaudrate = speedToBaud[speed]; + } +} + +void i2cInit(I2CDevice device) +{ + if (device < 0 || device >= I2CDEV_COUNT) { + return; + } + + ioTag_t sdaTag, sclTag; + + switch (device) { +#ifdef USE_I2C_DEVICE_1 + case I2CDEV_1: + sdaTag = IO_TAG(I2C1_SDA); + sclTag = IO_TAG(I2C1_SCL); + break; +#endif +#ifdef USE_I2C_DEVICE_2 + case I2CDEV_2: + sdaTag = IO_TAG(I2C2_SDA); + sclTag = IO_TAG(I2C2_SCL); + break; +#endif + default: + return; + } + + const uint sdaGpio = ioTagToGpio(sdaTag); + const uint sclGpio = ioTagToGpio(sclTag); + i2c_inst_t *hw = gpioToI2cHw(sdaGpio); + + /* On-chip pull-ups are safe defaults; external resistors (typically 4.7 kΩ) + * will dominate if fitted on the sensor board. */ + gpio_set_function(sdaGpio, GPIO_FUNC_I2C); + gpio_set_function(sclGpio, GPIO_FUNC_I2C); + gpio_pull_up(sdaGpio); + gpio_pull_up(sclGpio); + + i2c_init(hw, i2cBaudrate); + + i2cState[device].hw = hw; + i2cState[device].initialised = true; +} + +bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, + const uint8_t *data, bool allowRawAccess) +{ + if (device < 0 || device >= I2CDEV_COUNT || !i2cState[device].initialised) { + return false; + } + + i2c_inst_t *hw = i2cState[device].hw; + int ret; + + if (reg_ == 0xFF && allowRawAccess) { + ret = i2c_write_timeout_us(hw, addr_, data, len_, false, RP2350_I2C_TIMEOUT_US); + } else { + if (len_ > I2C_MAX_WRITE_LEN) { + return false; + } + uint8_t buf[I2C_MAX_WRITE_LEN + 1]; + buf[0] = reg_; + memcpy(&buf[1], data, len_); + ret = i2c_write_timeout_us(hw, addr_, buf, (size_t)(len_ + 1u), + false, RP2350_I2C_TIMEOUT_US); + } + + if (ret < 0) { + i2cErrorCount++; + return false; + } + return true; +} + +bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data, + bool allowRawAccess) +{ + return i2cWriteBuffer(device, addr_, reg, 1, &data, allowRawAccess); +} + +bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, + uint8_t *buf, bool allowRawAccess) +{ + if (device < 0 || device >= I2CDEV_COUNT || !i2cState[device].initialised) { + return false; + } + + i2c_inst_t *hw = i2cState[device].hw; + int ret; + + if (reg == 0xFF && allowRawAccess) { + ret = i2c_read_timeout_us(hw, addr_, buf, len, false, RP2350_I2C_TIMEOUT_US); + } else { + ret = i2c_write_timeout_us(hw, addr_, ®, 1, + true /* nostop — generates repeated start */, + RP2350_I2C_TIMEOUT_US); + if (ret < 0) { + i2cErrorCount++; + return false; + } + ret = i2c_read_timeout_us(hw, addr_, buf, len, false, RP2350_I2C_TIMEOUT_US); + } + + if (ret < 0) { + i2cErrorCount++; + return false; + } + return true; +} + +bool i2cBusy(I2CDevice device, bool *error) +{ + UNUSED(device); + if (error) { + *error = false; + } + /* Blocking implementation — transfers complete before returning */ + return false; +} + +uint16_t i2cGetErrorCounter(void) +{ + return i2cErrorCount; +} + +#endif /* USE_I2C */ diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index ff687984006..5cd3962f8eb 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -37,6 +37,10 @@ #define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_DOWN) #define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_MODE_MUX, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_UP) #define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE) +#elif defined(RP2350) +/* RP2350 ioConfig_t: bit 0 = direction (1=output), bit 5 = pull-up, bit 6 = pull-down. + * CS is a plain push-pull output with no pull resistors. */ +#define SPI_IO_CS_CFG 0x01 #endif /* diff --git a/src/main/drivers/bus_spi_rp2350.c b/src/main/drivers/bus_spi_rp2350.c new file mode 100644 index 00000000000..dee91f2ea7b --- /dev/null +++ b/src/main/drivers/bus_spi_rp2350.c @@ -0,0 +1,258 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * RP2350 SPI driver — blocking, Pico SDK hardware_spi. + * + * Implements the INAV bus_spi.h interface using the Pico SDK blocking API. + * DMA is not used; all transfers complete before returning. This is + * sufficient for sensor bring-up (gyro, baro, flash) and can be extended + * with DMA in a later milestone. + * + * Hardware mapping (Option C pin plan): + * INAV SPIDEV_1 → RP2350 spi0 → GP4 (MISO / PA4), GP6 (SCK / PA6), GP7 (MOSI / PA7) + * INAV SPIDEV_2 → RP2350 spi1 → configured via SPI2_* defines if needed + * + * SPI instance selection: the RP2350 assigns GPIOs to spi0 or spi1 in + * groups of 8: GP0–7 and GP16–23 → spi0; GP8–15 and GP24–31 → spi1. + * Formula: ((scl_gpio >> 3) & 1) ? spi1 : spi0. + * + * Mode: + * leadingEdge = true → Mode 0 (CPOL=0, CPHA=0) — most sensors + * leadingEdge = false → Mode 3 (CPOL=1, CPHA=1) — some NOR flash + * + * MISO pull-up: enabled on init to prevent MISO from floating when + * multiple slaves share the bus and one is deselected. + * + * Reference: Betaflight src/platform/PICO/bus_spi_pico.c + * INAV src/main/drivers/bus_spi.h + */ + +#include +#include +#include + +#include "platform.h" + +#ifdef USE_SPI + +#include "common/utils.h" +#include "drivers/bus_spi.h" +#include "drivers/io.h" +#include "drivers/io_def.h" + +#include "hardware/gpio.h" +#include "hardware/spi.h" + +/* Speed table: SPIClockSpeed_e → baud rate (Hz) */ +static const uint32_t spiClockFreq[] = { + [SPI_CLOCK_INITIALIZATON] = 328125, /* very slow: safe for all devices at init */ + [SPI_CLOCK_SLOW] = 1000000, /* 1 MHz */ + [SPI_CLOCK_STANDARD] = 10000000, /* 10 MHz */ + [SPI_CLOCK_FAST] = 20000000, /* 20 MHz */ + [SPI_CLOCK_ULTRAFAST] = 40000000, /* 40 MHz — RP2350 at 150 MHz easily supports this */ +}; + +typedef struct { + spi_inst_t *hw; + uint gpio_sck; + uint gpio_miso; + uint gpio_mosi; + volatile uint16_t errorCount; + bool initialised; + bool leadingEdge; +} rp2350SpiState_t; + +static rp2350SpiState_t spiState[SPIDEV_COUNT]; + +/* + * Map a SCK GPIO number to the RP2350 SPI hardware instance. + * GP0–7 and GP16–23 → spi0; GP8–15 and GP24–31 → spi1. + * Formula: group = gpio >> 3; spi1 if group is odd. + */ +static spi_inst_t *gpioToSpiHw(uint gpio) +{ + return ((gpio >> 3u) & 1u) ? spi1 : spi0; +} + +static inline uint ioTagToGpio(ioTag_t tag) +{ + return (uint)(DEFIO_TAG_GPIOID(tag) * 16u + DEFIO_TAG_PIN(tag)); +} + +/* ─── Device ↔ instance mapping ──────────────────────────────────────────── */ + +SPIDevice spiDeviceByInstance(SPI_TypeDef *instance) +{ + if (instance == SPI1) return SPIDEV_1; + if (instance == SPI2) return SPIDEV_2; + return SPIINVALID; +} + +SPI_TypeDef *spiInstanceByDevice(SPIDevice device) +{ + switch (device) { + case SPIDEV_1: return SPI1; + case SPIDEV_2: return SPI2; + default: return NULL; + } +} + +/* ─── Initialisation ─────────────────────────────────────────────────────── */ + +bool spiInitDevice(SPIDevice device, bool leadingEdge) +{ + if (device < 0 || device >= SPIDEV_COUNT) { + return false; + } + + ioTag_t sckTag, misoTag, mosiTag; + + switch (device) { +#ifdef USE_SPI_DEVICE_1 + case SPIDEV_1: + sckTag = IO_TAG(SPI1_SCK_PIN); + misoTag = IO_TAG(SPI1_MISO_PIN); + mosiTag = IO_TAG(SPI1_MOSI_PIN); + break; +#endif +#ifdef USE_SPI_DEVICE_2 + case SPIDEV_2: + sckTag = IO_TAG(SPI2_SCK_PIN); + misoTag = IO_TAG(SPI2_MISO_PIN); + mosiTag = IO_TAG(SPI2_MOSI_PIN); + break; +#endif + default: + return false; + } + + const uint gpioSck = ioTagToGpio(sckTag); + const uint gpioMiso = ioTagToGpio(misoTag); + const uint gpioMosi = ioTagToGpio(mosiTag); + spi_inst_t *hw = gpioToSpiHw(gpioSck); + + gpio_set_function(gpioSck, GPIO_FUNC_SPI); + gpio_set_function(gpioMosi, GPIO_FUNC_SPI); + gpio_set_function(gpioMiso, GPIO_FUNC_SPI); + + /* Pull MISO up: prevents the line from floating when a slave is + * deselected on a shared bus (e.g. gyro + flash on the same SPI). */ + gpio_pull_up(gpioMiso); + + /* Fast slew on SCK: reduces edge-to-edge time at high data rates. */ + gpio_set_slew_rate(gpioSck, GPIO_SLEW_RATE_FAST); + + /* Initialise hardware at a slow safe rate; callers use spiSetSpeed(). */ + spi_init(hw, spiClockFreq[SPI_CLOCK_INITIALIZATON]); + + spi_set_format(hw, 8, + leadingEdge ? SPI_CPOL_0 : SPI_CPOL_1, + leadingEdge ? SPI_CPHA_0 : SPI_CPHA_1, + SPI_MSB_FIRST); + + spiState[device].hw = hw; + spiState[device].gpio_sck = gpioSck; + spiState[device].gpio_miso = gpioMiso; + spiState[device].gpio_mosi = gpioMosi; + spiState[device].leadingEdge = leadingEdge; + spiState[device].errorCount = 0; + spiState[device].initialised = true; + + return true; +} + +/* ─── Speed control ──────────────────────────────────────────────────────── */ + +void spiSetSpeed(SPI_TypeDef *instance, SPIClockSpeed_e speed) +{ + const SPIDevice device = spiDeviceByInstance(instance); + if (device == SPIINVALID || !spiState[device].initialised) { + return; + } + if ((size_t)speed >= ARRAYLEN(spiClockFreq)) { + return; + } + spi_set_baudrate(spiState[device].hw, spiClockFreq[speed]); +} + +/* ─── Transfers ──────────────────────────────────────────────────────────── */ + +bool spiTransfer(SPI_TypeDef *instance, uint8_t *rxData, const uint8_t *txData, int len) +{ + const SPIDevice device = spiDeviceByInstance(instance); + if (device == SPIINVALID || !spiState[device].initialised || len <= 0) { + return false; + } + + spi_inst_t *hw = spiState[device].hw; + + if (txData && rxData) { + spi_write_read_blocking(hw, txData, rxData, (size_t)len); + } else if (txData) { + spi_write_blocking(hw, txData, (size_t)len); + } else if (rxData) { + /* 0xFF keeps MOSI high — required by SD cards and some flash chips. */ + spi_read_blocking(hw, 0xFF, rxData, (size_t)len); + } else { + return false; + } + + return true; +} + +uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in) +{ + uint8_t out; + spiTransfer(instance, &out, &in, 1); + return out; +} + +/* ─── Status ─────────────────────────────────────────────────────────────── */ + +bool spiIsBusBusy(SPI_TypeDef *instance) +{ + /* Blocking implementation — transfers complete before returning. */ + UNUSED(instance); + return false; +} + +uint16_t spiGetErrorCounter(SPI_TypeDef *instance) +{ + const SPIDevice device = spiDeviceByInstance(instance); + if (device == SPIINVALID) { + return 0; + } + return spiState[device].errorCount; +} + +void spiResetErrorCounter(SPI_TypeDef *instance) +{ + const SPIDevice device = spiDeviceByInstance(instance); + if (device != SPIINVALID) { + spiState[device].errorCount = 0; + } +} + +#endif /* USE_SPI */ diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index 60105de90f1..3ef0ef32417 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -4,7 +4,7 @@ #include "platform.h" -#if !defined(SITL_BUILD) +#if !defined(SITL_BUILD) && !defined(RP2350) #include "build/assert.h" diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index b13b73cbfd2..f08b5ba7fcf 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -147,7 +147,7 @@ uint32_t IO_EXTI_Line(IO_t io) } #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(AT32F43x) return 1 << IO_GPIOPinIdx(io); -#elif defined (SITL_BUILD) +#elif defined(SITL_BUILD) || defined(RP2350) return 0; #else # error "Unknown target type" diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index f08da7393dd..b256f04bfb8 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -88,6 +88,18 @@ #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT, GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE) #define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT, GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_UP) +#elif defined(RP2350) + +// RP2350 IO config encoding: bit 0 = direction (1=output), bit 5 = pullup, bit 6 = pulldown +# define IOCFG_OUT_PP 0x01 +# define IOCFG_OUT_OD 0x01 +# define IOCFG_AF_PP 0x01 +# define IOCFG_AF_OD 0x01 +# define IOCFG_AF_OD_UP 0x21 +# define IOCFG_IPD 0x40 +# define IOCFG_IPU 0x20 +# define IOCFG_IN_FLOATING 0x00 + #elif defined(UNIT_TEST) || defined(SITL_BUILD) # define IOCFG_OUT_PP 0 diff --git a/src/main/drivers/io_rp2350.c b/src/main/drivers/io_rp2350.c new file mode 100644 index 00000000000..da8f4abcfb3 --- /dev/null +++ b/src/main/drivers/io_rp2350.c @@ -0,0 +1,245 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + * + * RP2350 GPIO abstraction for INAV. + * + * RP2350 has a flat GPIO model (GPIO 0-29, single port). + * We map these into INAV's two-port model: + * Port A (gpioid 0) = GPIO 0-15 + * Port B (gpioid 1) = GPIO 16-29 + * + * Unlike STM32, the pin field in ioRec_t stores the raw GPIO number + * (not a bitmask), and IO operations use Pico SDK gpio functions. + */ + +#include "platform.h" + +#include "build/assert.h" +#include "common/utils.h" + +#include "drivers/io.h" +#include "drivers/io_impl.h" + +#include "hardware/gpio.h" + +// Port definition tables (from io_def_generated.h via TARGET_IO_PORTx) +#if DEFIO_PORT_USED_COUNT > 0 +static const uint16_t ioDefUsedMask[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_USED_LIST }; +static const uint8_t ioDefUsedOffset[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_OFFSET_LIST }; +#else +static const uint16_t ioDefUsedMask[1] = {0}; +static const uint8_t ioDefUsedOffset[1] = {0}; +#endif + +ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; + +static inline uint8_t portPinToGpio(unsigned port, unsigned pin) +{ + return (uint8_t)(port * 16 + pin); +} + +void IOInitGlobal(void) +{ + ioRec_t *ioRec = ioRecs; + + for (unsigned port = 0; port < ARRAYLEN(ioDefUsedMask); port++) { + for (unsigned pin = 0; pin < sizeof(ioDefUsedMask[0]) * 8; pin++) { + if (ioDefUsedMask[port] & (1 << pin)) { + ioRec->gpio = NULL; + // Store raw GPIO number (not a bitmask) + ioRec->pin = portPinToGpio(port, pin); + ioRec++; + } + } + } +} + +ioRec_t *IO_Rec(IO_t io) +{ + ASSERT(io != NULL); + ASSERT((ioRec_t *)io >= &ioRecs[0]); + ASSERT((ioRec_t *)io < &ioRecs[DEFIO_IO_USED_COUNT]); + return io; +} + +GPIO_TypeDef *IO_GPIO(IO_t io) +{ + const ioRec_t *ioRec = IO_Rec(io); + return ioRec->gpio; +} + +uint16_t IO_Pin(IO_t io) +{ + const ioRec_t *ioRec = IO_Rec(io); + return ioRec->pin; +} + +int IO_GPIOPortIdx(IO_t io) +{ + if (!io) { + return -1; + } + return IO_Pin(io) >> 4; +} + +int IO_GPIOPinIdx(IO_t io) +{ + if (!io) { + return -1; + } + return IO_Pin(io); +} + +int IO_GPIO_PortSource(IO_t io) +{ + return IO_GPIOPortIdx(io); +} + +int IO_GPIO_PinSource(IO_t io) +{ + return IO_GPIOPinIdx(io); +} + +uint32_t IO_EXTI_Line(IO_t io) +{ + UNUSED(io); + return 0; +} + +bool IORead(IO_t io) +{ + if (!io) { + return false; + } + return gpio_get(IO_Pin(io)); +} + +void IOWrite(IO_t io, bool hi) +{ + if (!io) { + return; + } + gpio_put(IO_Pin(io), hi); +} + +void IOHi(IO_t io) +{ + if (!io) { + return; + } + gpio_put(IO_Pin(io), 1); +} + +void IOLo(IO_t io) +{ + if (!io) { + return; + } + gpio_put(IO_Pin(io), 0); +} + +void IOToggle(IO_t io) +{ + if (!io) { + return; + } + gpio_put(IO_Pin(io), !gpio_get(IO_Pin(io))); +} + +void IOInit(IO_t io, resourceOwner_e owner, resourceType_e resource, uint8_t index) +{ + if (!io) { + return; + } + ioRec_t *ioRec = IO_Rec(io); + ioRec->owner = owner; + ioRec->resource = resource; + ioRec->index = index; +} + +void IORelease(IO_t io) +{ + if (!io) { + return; + } + ioRec_t *ioRec = IO_Rec(io); + ioRec->owner = OWNER_FREE; +} + +resourceOwner_e IOGetOwner(IO_t io) +{ + if (!io) { + return OWNER_FREE; + } + const ioRec_t *ioRec = IO_Rec(io); + return ioRec->owner; +} + +resourceType_e IOGetResource(IO_t io) +{ + const ioRec_t *ioRec = IO_Rec(io); + return ioRec->resource; +} + +void IOConfigGPIO(IO_t io, ioConfig_t cfg) +{ + if (!io) { + return; + } + + uint16_t ioPin = IO_Pin(io); + + // Only call gpio_init if pin hasn't been configured yet. + // This prevents resetting output levels on already-configured SPI CS pins. + gpio_function_t currentFunction = gpio_get_function(ioPin); + if (currentFunction == GPIO_FUNC_NULL) { + gpio_init(ioPin); + } + + gpio_set_dir(ioPin, (cfg & 0x01)); + gpio_set_pulls(ioPin, (cfg >> 5) & 0x01, (cfg >> 6) & 0x01); +} + +void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af) +{ + UNUSED(af); + IOConfigGPIO(io, cfg); +} + +IO_t IOGetByTag(ioTag_t tag) +{ + const int portIdx = DEFIO_TAG_GPIOID(tag); + const int pinIdx = DEFIO_TAG_PIN(tag); + + if (portIdx < 0 || portIdx >= DEFIO_PORT_USED_COUNT) { + return NULL; + } + + if (!(ioDefUsedMask[portIdx] & (1 << pinIdx))) { + return NULL; + } + + int offset = __builtin_popcount(((1 << pinIdx) - 1) & ioDefUsedMask[portIdx]); + offset += ioDefUsedOffset[portIdx]; + return ioRecs + offset; +} diff --git a/src/main/drivers/light_ws2811strip_rp2350.c b/src/main/drivers/light_ws2811strip_rp2350.c new file mode 100644 index 00000000000..849dc5cb4c8 --- /dev/null +++ b/src/main/drivers/light_ws2811strip_rp2350.c @@ -0,0 +1,282 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * RP2350 WS2812 LED strip driver — PIO2 + DMA. + * + * Replaces the STM32 timer/DMA implementation in light_ws2811strip.c for + * RP2350 targets. Uses PIO2 (PIO_LEDSTRIP_INDEX = 2) with a 4-instruction + * WS2812 program and a DMA channel to stream GRB words to the PIO TX FIFO. + * + * Replaces the generic light_ws2811strip.c (excluded from RP2350 builds in + * cmake/rp2350.cmake) and provides all functions declared in + * drivers/light_ws2811strip.h. + * + * Pin: WS2811_PIN (GP22 = PB6 in target.h) — free from flash/I2C/UART/SPI. + * PIO: PIO2 SM0, loaded once at ws2811LedStripInit(). + * DMA: one channel, polled for completion — no IRQ needed. + * + * GRB word layout in led_data[] (WS2812 native order, left-shift OSR, 24-bit + * autopull): + * bits 31:24 = G[7:0] — transmitted first + * bits 23:16 = R[7:0] + * bits 15: 8 = B[7:0] — transmitted last + * bits 7: 0 = 0x00 — discarded after 24-bit autopull fires + * + * Reference: Betaflight src/platform/PICO/light_ws2811strip_pico.c + */ + +#include +#include +#include + +#include "platform.h" + +#ifdef USE_LED_STRIP + +#include "common/color.h" +#include "common/colorconversion.h" +#include "common/utils.h" + +#include "config/parameter_group_ids.h" +#include "drivers/io.h" +#include "drivers/light_ws2811strip.h" +#include "fc/settings.h" + +#include "hardware/clocks.h" +#include "hardware/dma.h" +#include "hardware/pio.h" + +/* ─── PIO program ─────────────────────────────────────────────────────────── */ +/* + * 4-instruction WS2812 program. Timing (10 cycles/bit at 800 kHz): + * T1=3, T2=3, T3=4 → period = 10 cycles + * 0-bit: high=3, low=7 1-bit: high=6, low=4 + * Identical to BF's light_ws2811strip_pico.c. + */ +#define WS2812_WRAP_TARGET 0 +#define WS2812_WRAP 3 +#define WS2812_PIO_VERSION 0 +#define WS2812_T1 3 +#define WS2812_T2 3 +#define WS2812_T3 4 + +static const uint16_t ws2812_program_instructions[] = { + // .wrap_target + 0x6321, /* 0: out x, 1 side 0 [3] */ + 0x1223, /* 1: jmp !x, 3 side 1 [2] */ + 0x1200, /* 2: jmp 0 side 1 [2] */ + 0xa242, /* 3: nop side 0 [2] */ + // .wrap +}; + +static const struct pio_program ws2812_program = { + .instructions = ws2812_program_instructions, + .length = 4, + .origin = -1, + .pio_version = WS2812_PIO_VERSION, + .used_gpio_ranges = 0x0, +}; + +/* ─── State ───────────────────────────────────────────────────────────────── */ + +static hsvColor_t ledColorBuffer[WS2811_LED_STRIP_LENGTH]; +static uint32_t led_data[WS2811_LED_STRIP_LENGTH]; /* GRB words for PIO */ + +static PIO ledStripPio = NULL; +static uint ledStripSm = 0; +static int ledStripDmaCh = -1; +static bool ledStripInitialised = false; + +/* ─── PG registration ─────────────────────────────────────────────────────── */ + +PG_REGISTER_WITH_RESET_TEMPLATE(ledPinConfig_t, ledPinConfig, PG_LEDPIN_CONFIG, 0); + +PG_RESET_TEMPLATE(ledPinConfig_t, ledPinConfig, + .led_pin_pwm_mode = SETTING_LED_PIN_PWM_MODE_DEFAULT +); + +/* ─── Color buffer helpers (identical to generic light_ws2811strip.c) ─────── */ + +void setLedHsv(uint16_t index, const hsvColor_t *color) +{ + ledColorBuffer[index] = *color; +} + +void getLedHsv(uint16_t index, hsvColor_t *color) +{ + *color = ledColorBuffer[index]; +} + +void setLedValue(uint16_t index, const uint8_t value) +{ + ledColorBuffer[index].v = value; +} + +void scaleLedValue(uint16_t index, const uint8_t scalePercent) +{ + ledColorBuffer[index].v = (uint8_t)((uint16_t)ledColorBuffer[index].v * scalePercent / 100); +} + +void setStripColor(const hsvColor_t *color) +{ + for (uint16_t i = 0; i < WS2811_LED_STRIP_LENGTH; i++) { + setLedHsv(i, color); + } +} + +void setStripColors(const hsvColor_t *colors) +{ + for (uint16_t i = 0; i < WS2811_LED_STRIP_LENGTH; i++) { + setLedHsv(i, colors++); + } +} + +/* ─── Status ─────────────────────────────────────────────────────────────── */ + +bool isWS2811LedStripReady(void) +{ + if (!ledStripInitialised || ledStripDmaCh < 0) { + return false; + } + return !dma_channel_is_busy((uint)ledStripDmaCh); +} + +/* ─── Hardware init ──────────────────────────────────────────────────────── */ + +void ws2811LedStripInit(void) +{ + /* WS2811_PIN is defined in target.h (e.g. PB6 = GP22). + * DEFIO_TAG_GPIOID gives the port index (0=PA,1=PB); DEFIO_TAG_PIN + * gives the bit within the port. GPIO number = gpioid*16 + pin. */ + const ioTag_t tag = IO_TAG(WS2811_PIN); + const uint gpio = (uint)(DEFIO_TAG_GPIOID(tag) * 16 + DEFIO_TAG_PIN(tag)); + + ledStripPio = PIO_INSTANCE(PIO_LEDSTRIP_INDEX); + + /* For pins 32..47 the GPIO base must be shifted (RP2350B only). + * GP22 is < 32 so this is a no-op on Pico 2, but keep it for portability. */ + if (gpio >= 32) { + pio_set_gpio_base(ledStripPio, 16u); + } + + if (!pio_can_add_program(ledStripPio, &ws2812_program)) { + return; + } + const uint offset = (uint)pio_add_program(ledStripPio, &ws2812_program); + + const int sm = pio_claim_unused_sm(ledStripPio, false); + if (sm < 0) { + return; + } + ledStripSm = (uint)sm; + + pio_gpio_init(ledStripPio, gpio); + pio_sm_set_consecutive_pindirs(ledStripPio, ledStripSm, gpio, 1, true); + + pio_sm_config c = pio_get_default_sm_config(); + sm_config_set_wrap(&c, offset + WS2812_WRAP_TARGET, offset + WS2812_WRAP); + sm_config_set_sideset(&c, 1, false, false); + sm_config_set_sideset_pins(&c, gpio); + /* Left shift (MSB first), autopull after 24 bits (RGB; not RGBW) */ + sm_config_set_out_shift(&c, false, true, 24); + sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX); + + const int cycles_per_bit = WS2812_T1 + WS2812_T2 + WS2812_T3; + const float div = (float)clock_get_hz(clk_sys) / ((float)WS2811_CARRIER_HZ * (float)cycles_per_bit); + sm_config_set_clkdiv(&c, div); + + pio_sm_init(ledStripPio, ledStripSm, offset, &c); + pio_sm_set_enabled(ledStripPio, ledStripSm, true); + + const int dma_ch = dma_claim_unused_channel(false); + if (dma_ch < 0) { + return; + } + ledStripDmaCh = dma_ch; + + dma_channel_config dc = dma_channel_get_default_config((uint)ledStripDmaCh); + channel_config_set_transfer_data_size(&dc, DMA_SIZE_32); + channel_config_set_read_increment(&dc, true); + channel_config_set_write_increment(&dc, false); + channel_config_set_dreq(&dc, pio_get_dreq(ledStripPio, ledStripSm, true)); + + dma_channel_configure( + (uint)ledStripDmaCh, + &dc, + &ledStripPio->txf[ledStripSm], /* write: PIO TX FIFO */ + NULL, /* read: set at start time */ + WS2811_LED_STRIP_LENGTH, + false + ); + + memset(ledColorBuffer, 0, sizeof(ledColorBuffer)); + memset(led_data, 0, sizeof(led_data)); + + ledStripInitialised = true; + + /* Send an all-zeros frame to reset any previously lit strip */ + ws2811UpdateStrip(); +} + +/* ─── Strip update ───────────────────────────────────────────────────────── */ + +void ws2811UpdateStrip(void) +{ + if (!ledStripInitialised || ledStripDmaCh < 0) { + return; + } + /* Don't start a new frame while the previous one is still in flight */ + if (dma_channel_is_busy((uint)ledStripDmaCh)) { + return; + } + + /* Convert HSV → GRB. WS2812 bit order: G[7:0] R[7:0] B[7:0], MSB first. + * Pack into bits 31:8 of the 32-bit word; the PIO left-shifts 24 bits out + * then autopulls the next word (bottom 8 bits are discarded). */ + for (uint16_t i = 0; i < WS2811_LED_STRIP_LENGTH; i++) { + const rgbColor24bpp_t *rgb = hsvToRgb24(&ledColorBuffer[i]); + led_data[i] = ((uint32_t)rgb->rgb.g << 24) + | ((uint32_t)rgb->rgb.r << 16) + | ((uint32_t)rgb->rgb.b << 8); + } + + dma_channel_set_read_addr((uint)ledStripDmaCh, led_data, false); + dma_channel_set_trans_count((uint)ledStripDmaCh, WS2811_LED_STRIP_LENGTH, false); + dma_channel_start((uint)ledStripDmaCh); +} + +/* ─── Stubs for BF-only / timer-based API ────────────────────────────────── */ + +/* Called only when a plain-LED (non-WS2812) PWM pin mode is selected. + * PIO-based WS2812 does not support this mode; leave as no-ops. */ +void ledPinStartPWM(uint16_t value) { UNUSED(value); } +void ledPinStopPWM(void) { } + +/* Declared in the header for completeness; not called by INAV at runtime. */ +void ws2811LedStripHardwareInit(void) { } +void ws2811LedStripDMAEnable(void) { } +bool ws2811LedStripDMAInProgress(void) { return !isWS2811LedStripReady(); } + +#endif /* USE_LED_STRIP */ diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 2d01127a504..dc6248e911e 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -21,7 +21,7 @@ #include "platform.h" -#if !defined(SITL_BUILD) +#if !defined(SITL_BUILD) && !defined(RP2350) #include "build/debug.h" #include "common/log.h" diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 619f4b95db5..5d16c62d773 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -22,7 +22,7 @@ #include "platform.h" -#if !defined(SITL_BUILD) +#if !defined(SITL_BUILD) && !defined(RP2350) #include "build/debug.h" diff --git a/src/main/drivers/pwm_output_rp2350.c b/src/main/drivers/pwm_output_rp2350.c new file mode 100644 index 00000000000..6cdfcd20fe5 --- /dev/null +++ b/src/main/drivers/pwm_output_rp2350.c @@ -0,0 +1,637 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * RP2350 motor output — DShot 600 via PIO0 — Milestone 7 + * + * Maps INAV's motor output API onto PIO0 state machines using the DShot 600 + * protocol. One SM per motor; up to 4 motors on a single PIO block. + * + * Motor pin assignments (from target.h): + * M1 → MOTOR1_PIN (GP8) M2 → MOTOR2_PIN (GP9) + * M3 → MOTOR3_PIN (GP10) M4 → MOTOR4_PIN (GP11) + * + * All SMs are stopped, their TX FIFOs loaded, then restarted together via + * pio_enable_sm_mask_in_sync() so every motor frame begins on the same + * system-clock edge — required by multirotor ESC sync expectations. + * + * PIO program is pre-assembled from betaflight/src/platform/PICO/dshot.pio + * (program "dshot_600"). Embedding pre-assembled instructions avoids a + * pioasm build step and matches the approach used by uart_pio_rp2350.c. + * + * DShot packet format (16 bits, MSB first): + * [15:5] 11-bit throttle (0 = stop, 1-47 = commands, 48-2047 = throttle) + * [4] telemetry request + * [3:0] 4-bit XOR checksum of bits [15:4] + */ + +#include "platform.h" + +#ifdef RP2350 + +#include +#include + +#include "build/build_config.h" + +#include "common/utils.h" + +#include "drivers/io_def.h" +#include "drivers/io_types.h" +#include "drivers/pwm_mapping.h" +#include "drivers/pwm_output.h" +#include "drivers/timer.h" + +#include "flight/mixer.h" + +#include "hardware/clocks.h" +#include "hardware/gpio.h" +#include "hardware/pio.h" +#include "hardware/pwm.h" + +/* ── Pre-assembled DShot 600 PIO program ───────────────────────────────────── + * + * Source: betaflight/src/platform/PICO/dshot.pio, program "dshot_600" + * Compiled with: pioasm dshot.pio /dev/stdout + * Copyright (c) 2021-2024 Betaflight contributors. GPL-3.0. + * + * Bit period = DSHOT_BIT_PERIOD (40) PIO cycles. The SM clock divider is set + * so one PIO cycle ≈ 1.667 µs / 40 ≈ 41.67 ns at the configured system clock + * (currently 192 MHz → clkdiv = 8.0 exactly). + * + * Signal encoding (non-bidirectional): + * '1' bit → pin HIGH for 30 cycles then LOW for 10 + * '0' bit → pin HIGH for 15 cycles then LOW for 25 + * + * The SM blocks on a TX-FIFO pull. It discards the top 16 bits of the + * 32-bit word ("out y, 16") then shifts out the lower 16, MSB first. + */ +#define DSHOT_BIT_PERIOD 40 /* PIO cycles per DShot 600 bit */ +#define DSHOT_600_WRAP_TARGET 0 +#define DSHOT_600_WRAP 12 + +static const uint16_t dshotProgramInstructions[] = { + // .wrap_target + 0xff00, // 0: set pins, 0 [31] — inter-frame gap (low) + 0xb442, // 1: nop [20] — extend gap to ≥2 µs + 0x80a0, // 2: pull block — wait for next packet + 0x6050, // 3: out y, 16 — discard top 16 bits + 0x6041, // 4: out y, 1 — shift next bit into y + 0x006a, // 5: jmp !y, 10 — branch on bit=0 + 0xfd01, // 6: set pins, 1 [29] — bit=1: high for 30 cyc + 0xe600, // 7: set pins, 0 [6] — then low for 10 cyc + 0x00e4, // 8: jmp !osre, 4 — more bits? loop + 0x0000, // 9: jmp 0 — frame done → wrap + 0xee01, // 10: set pins, 1 [14] — bit=0: high for 15 cyc + 0xf400, // 11: set pins, 0 [20] — then low for 25 cyc + 0x01e4, // 12: jmp !osre, 4 [1] — more bits? loop + // .wrap +}; + +static const struct pio_program dshotProgram = { + .instructions = dshotProgramInstructions, + .length = 13, + .origin = -1, + .pio_version = 0, +#if PICO_PIO_VERSION > 0 + .used_gpio_ranges = 0x0, +#endif +}; + +static inline pio_sm_config dshotGetDefaultConfig(uint offset) +{ + pio_sm_config c = pio_get_default_sm_config(); + sm_config_set_wrap(&c, offset + DSHOT_600_WRAP_TARGET, + offset + DSHOT_600_WRAP); + return c; +} + +/* ── Module state ────────────────────────────────────────────────────────── */ + +#define DSHOT_MAX_MOTORS 4 + +typedef struct { + uint pin; + uint sm; + uint16_t value; + bool requestTelemetry; +} dshotMotor_t; + +static dshotMotor_t dshotMotors[DSHOT_MAX_MOTORS]; +static uint dshotMotorCount = 0; +static bool dshotInitialized = false; +static bool dshotEnabled = true; +static uint dshotProgramOffset; + +static motorPwmProtocolTypes_e initProtocol = PWM_TYPE_STANDARD; +static pwmInitError_e rp2350PwmError = PWM_INIT_ERROR_NONE; + +/* ── Standard-PWM motor state ────────────────────────────────────────────── */ + +/* + * Non-DShot motor protocols (Standard PWM, Oneshot125, Brushed, etc.) use + * the same RP2350 hardware PWM peripheral as servos, on the motor GPIO pins + * assigned from timerHardware[] (GP8–GP11 / slices 4–5 by default). + * + * Update rate 400 Hz → period = 2.5 ms; with 1 µs/tick: wrap = 2499. + * pwm_set_gpio_level(pin, us) writes pulse width in µs directly. + * The INAV motor value passed to pwmWriteMotor() is already in µs (1000–2000). + */ +#define MOTOR_PWM_WRAP 2499u /* 2.5 ms period = 400 Hz at 1 µs/tick */ +#define MOTOR_MIN_US 1000u +#define MOTOR_MAX_US 2000u + +static uint8_t motorPwmPins[DSHOT_MAX_MOTORS]; +static uint8_t motorPwmCount = 0; +static bool motorPwmInitialized = false; +static bool motorPwmEnabled = true; + +/* ── Servo state ─────────────────────────────────────────────────────────── */ + +/* + * Servo PWM via hardware PWM slices (NOT PIO — different from DShot motors). + * 8 slices × 2 channels = 16 possible servo outputs. + * + * Timing: clkdiv = sysHz / 1_000_000 → 1 µs per tick; wrap = 19999 → 50 Hz. + * pwm_set_gpio_level(pin, us) sets pulse width directly in microseconds. + */ +#define RP2350_MAX_SERVOS 8u +#define SERVO_PWM_WRAP 19999u /* 20 ms period = 50 Hz at 1 µs/tick */ +#define SERVO_MIN_US 750u +#define SERVO_MAX_US 2250u +#define SERVO_DEFAULT_US 1500u /* center pulse */ + +static uint8_t servoHwPins[RP2350_MAX_SERVOS]; +static uint8_t servoCount = 0; +static bool servoInitialized = false; + +/* Pending DShot command (e.g. spin direction). Commands are sent 10×. */ +static dshotCommands_e pendingCmd = 0; +static int pendingCmdReps = 0; + +/* ── DShot packet construction ───────────────────────────────────────────── */ + +static uint16_t prepareDshotPacket(uint16_t value, bool requestTelemetry) +{ + uint16_t packet = ((uint16_t)(value << 1)) | (requestTelemetry ? 1u : 0u); + uint16_t csum = 0; + uint16_t csum_data = packet; + for (int i = 0; i < 3; i++) { + csum ^= csum_data; + csum_data >>= 4; + } + csum &= 0xfu; + return (packet << 4) | csum; +} + +/* ── Motor output API ────────────────────────────────────────────────────── */ + +void pwmWriteMotor(uint8_t index, uint16_t value) +{ + if (dshotInitialized) { + if (dshotEnabled && index < dshotMotorCount) { + dshotMotors[index].value = value; + } + } else if (motorPwmInitialized && motorPwmEnabled && index < motorPwmCount) { + /* value=0 means disarmed; output minimum throttle pulse */ + uint16_t us = (value == 0) ? MOTOR_MIN_US + : (uint16_t)constrain(value, MOTOR_MIN_US, MOTOR_MAX_US); + pwm_set_gpio_level(motorPwmPins[index], us); + } +} + +void pwmShutdownPulsesForAllMotors(uint8_t motorCount) +{ + if (dshotInitialized) { + for (uint8_t i = 0; i < motorCount && i < dshotMotorCount; i++) { + dshotMotors[i].value = 0; + } + pwmCompleteMotorUpdate(); + } else if (motorPwmInitialized) { + for (uint8_t i = 0; i < motorCount && i < motorPwmCount; i++) { + pwm_set_gpio_level(motorPwmPins[i], MOTOR_MIN_US); + } + } +} + +void pwmCompleteMotorUpdate(void) +{ + /* Standard PWM: pwm_set_gpio_level() takes effect immediately — no work needed */ + if (!dshotInitialized || !dshotEnabled || dshotMotorCount == 0) { + return; + } + + uint32_t motorMask = 0; + for (uint i = 0; i < dshotMotorCount; i++) { + motorMask |= 1u << dshotMotors[i].sm; + } + + /* Stop all SMs before loading FIFOs — required for simultaneous restart */ + pio_set_sm_mask_enabled(pio0, motorMask, false); + + for (uint i = 0; i < dshotMotorCount; i++) { + uint16_t value = dshotMotors[i].value; + bool telemetry = dshotMotors[i].requestTelemetry; + + if (pendingCmdReps > 0) { + value = (uint16_t)pendingCmd; + telemetry = true; + } + + uint16_t packet = prepareDshotPacket(value, telemetry); + /* Discard any stale packet left in the FIFO from a missed cycle */ + pio_sm_drain_tx_fifo(pio0, dshotMotors[i].sm); + /* PIO discards top 16 bits ("out y, 16") — packet in lower half */ + pio_sm_put(pio0, dshotMotors[i].sm, (uint32_t)packet); + dshotMotors[i].requestTelemetry = false; + } + + pio_enable_sm_mask_in_sync(pio0, motorMask); + + if (pendingCmdReps > 0) { + pendingCmdReps--; + } +} + +/* ── Motor enable / disable ──────────────────────────────────────────────── */ + +void pwmDisableMotors(void) +{ + dshotEnabled = false; + motorPwmEnabled = false; + for (uint i = 0; i < motorPwmCount; i++) { + pwm_set_gpio_level(motorPwmPins[i], MOTOR_MIN_US); + } +} + +void pwmEnableMotors(void) +{ + dshotEnabled = true; + motorPwmEnabled = true; +} + +/* ── Protocol queries ────────────────────────────────────────────────────── */ + +bool isMotorProtocolDshot(void) +{ + switch (initProtocol) { + case PWM_TYPE_DSHOT150: + case PWM_TYPE_DSHOT300: + case PWM_TYPE_DSHOT600: + return true; + default: + return false; + } +} + +bool isMotorProtocolDigital(void) +{ + return isMotorProtocolDshot(); +} + +/* ── DShot command queue ─────────────────────────────────────────────────── */ + +void initDShotCommands(void) +{ + pendingCmd = 0; + pendingCmdReps = 0; +} + +void sendDShotCommand(dshotCommands_e cmd) +{ + pendingCmd = cmd; + pendingCmdReps = 10; /* DShot spec: send each command 10 times */ +} + +/* ── Telemetry / pin tag ─────────────────────────────────────────────────── */ + +void pwmRequestMotorTelemetry(int motorIndex) +{ + if ((uint)motorIndex < dshotMotorCount) { + dshotMotors[motorIndex].requestTelemetry = true; + } +} + +ioTag_t pwmGetMotorPinTag(int motorIndex) +{ + UNUSED(motorIndex); + return IOTAG_NONE; +} + +/* ── GPIO helpers ────────────────────────────────────────────────────────── */ + +/* + * Convert an INAV ioTag_t to the raw RP2350 GPIO number. + * + * ioTag_t encoding: ((gpioid + 1) << 4) | pin + * gpioid 0 → Port A (GPIO 0–15) + * gpioid 1 → Port B (GPIO 16–29) + * + * So GPIO number = gpioid * 16 + pin + * PA8 (GPIO 8) → gpioid=0, pin=8 → 0*16+8 = 8 + * PB0 (GPIO 16) → gpioid=1, pin=0 → 1*16+0 = 16 + */ +static inline uint ioTagToGpioNum(ioTag_t tag) +{ + return (uint)(DEFIO_TAG_GPIOID(tag) * 16 + DEFIO_TAG_PIN(tag)); +} + +/* ── Motor and servo initialisation ───────────────────────────────────────── + * + * Iterates timerHardware[] (populated in target.c) to assign each GPIO + * to motor or servo output. The assignment for each PWM slice is decided + * once (when the first pin of that slice is processed) based on: + * + * timerOverrides(sliceId)->outputMode + * OUTPUT_MODE_MOTORS → whole slice is motor output + * OUTPUT_MODE_SERVOS → whole slice is servo output + * OUTPUT_MODE_AUTO → motor if motors still needed, servo otherwise + * + * Both channels on a slice always receive the same assignment because they + * share clkdiv/wrap registers and must run at the same update rate. + * + * Called from fc_init.c after the mixer has been configured, so + * getMotorCount() returns the correct value. + */ + +/* Per-slice assignment state (only used inside pwmMotorAndServoInit) */ +typedef enum { + SLICE_UNASSIGNED = 0, + SLICE_AS_MOTOR, + SLICE_AS_SERVO, +} sliceAssign_e; + +bool pwmMotorAndServoInit(void) +{ + if (dshotInitialized || motorPwmInitialized) { + return true; /* already initialized */ + } + + initProtocol = motorConfig()->motorPwmProtocol; + bool dshot = isMotorProtocolDshot(); + uint motorCount = (uint)getMotorCount(); + + /* ── DShot: load PIO program once ────────────────────────────────── */ + + float dshotClkdiv = 0.0f; + if (dshot) { + /* + * RP2350 PIO GPIO base: the only legal values are 0 (GP0–GP31) or 16 + * (GP16–GP47). RP2350 has GPIOs 0–29 so base=0 always covers all pins. + */ + if (pio_set_gpio_base(pio0, 0u) != PICO_OK) { + rp2350PwmError = PWM_INIT_ERROR_TIMER_INIT_FAILED; + return false; + } + int offset = pio_add_program(pio0, &dshotProgram); + if (offset < 0) { + rp2350PwmError = PWM_INIT_ERROR_TIMER_INIT_FAILED; + return false; + } + dshotProgramOffset = (uint)offset; + + /* + * Bit period varies by protocol; the PIO program uses DSHOT_BIT_PERIOD + * (40) cycles per bit. Adjust clkdiv so one PIO cycle equals the + * required nanoseconds for the selected speed: + * DShot 150: 6.667 µs / 40 = 166.7 ns/cycle → clkdiv = 32.0 @ 192 MHz + * DShot 300: 3.333 µs / 40 = 83.3 ns/cycle → clkdiv = 16.0 @ 192 MHz + * DShot 600: 1.667 µs / 40 = 41.7 ns/cycle → clkdiv = 8.0 @ 192 MHz + */ + float bitPeriodUs; + switch (initProtocol) { + case PWM_TYPE_DSHOT150: bitPeriodUs = 6.666667f; break; + case PWM_TYPE_DSHOT300: bitPeriodUs = 3.333333f; break; + default: bitPeriodUs = 1.666667f; break; /* DShot 600 */ + } + float clocks_per_us = (float)clock_get_hz(clk_sys) / 1000000.0f; + dshotClkdiv = (bitPeriodUs / (float)DSHOT_BIT_PERIOD) * clocks_per_us; + } + + /* ── Shared hardware-PWM clock divider (1 µs/tick) ───────────────── */ + + float clkdiv = (float)clock_get_hz(clk_sys) / 1000000.0f; + + /* ── Slice assignment tracking ────────────────────────────────────── */ + + sliceAssign_e sliceAssign[HARDWARE_TIMER_DEFINITION_COUNT]; + for (int s = 0; s < HARDWARE_TIMER_DEFINITION_COUNT; s++) { + sliceAssign[s] = SLICE_UNASSIGNED; + } + + uint32_t motorSliceInitMask = 0; + uint32_t servoSliceInitMask = 0; + uint motorIdx = 0; + uint servoIdx = 0; + + /* ── Main assignment loop ─────────────────────────────────────────── */ + + for (int i = 0; i < timerHardwareCount; i++) { + const timerHardware_t *timHw = &timerHardware[i]; + uint8_t sliceId = timer2id(timHw->tim); + if (sliceId >= HARDWARE_TIMER_DEFINITION_COUNT) { + continue; /* safety: unknown slice */ + } + uint gpio = ioTagToGpioNum(timHw->tag); + + /* First pin on this slice: determine assignment for the whole slice */ + if (sliceAssign[sliceId] == SLICE_UNASSIGNED) { + uint8_t mode = timerOverrides(sliceId)->outputMode; + if (mode == OUTPUT_MODE_MOTORS) { + sliceAssign[sliceId] = SLICE_AS_MOTOR; + } else if (mode == OUTPUT_MODE_SERVOS) { + sliceAssign[sliceId] = SLICE_AS_SERVO; + } else { + /* AUTO: motor if we still need motors, servo otherwise */ + sliceAssign[sliceId] = (motorIdx < motorCount) ? SLICE_AS_MOTOR + : SLICE_AS_SERVO; + } + } + + if (sliceAssign[sliceId] == SLICE_AS_MOTOR) { + if (motorIdx >= DSHOT_MAX_MOTORS) { + rp2350PwmError = PWM_INIT_ERROR_TOO_MANY_MOTORS; + return false; + } + if (dshot) { + /* ── DShot motor via PIO ─────────────────────────────── */ + int sm = pio_claim_unused_sm(pio0, false); + if (sm < 0) { + rp2350PwmError = PWM_INIT_ERROR_TIMER_INIT_FAILED; + return false; + } + pio_sm_config cfg = dshotGetDefaultConfig(dshotProgramOffset); + sm_config_set_set_pins(&cfg, gpio, 1); + pio_gpio_init(pio0, gpio); + pio_sm_set_consecutive_pindirs(pio0, (uint)sm, gpio, 1, true); + gpio_set_pulls(gpio, false, true); /* pulldown — idle low */ + sm_config_set_out_shift(&cfg, false, false, 32); /* left shift, no autopull */ + sm_config_set_fifo_join(&cfg, PIO_FIFO_JOIN_TX); + sm_config_set_clkdiv(&cfg, dshotClkdiv); + if (pio_sm_init(pio0, (uint)sm, dshotProgramOffset, &cfg) != PICO_OK) { + rp2350PwmError = PWM_INIT_ERROR_TIMER_INIT_FAILED; + return false; + } + pio_sm_set_enabled(pio0, (uint)sm, true); + + dshotMotors[motorIdx].pin = gpio; + dshotMotors[motorIdx].sm = (uint)sm; + dshotMotors[motorIdx].value = 0; + dshotMotors[motorIdx].requestTelemetry = false; + } else { + /* ── Standard hardware-PWM motor ─────────────────────── */ + gpio_set_function(gpio, GPIO_FUNC_PWM); + uint slice = pwm_gpio_to_slice_num(gpio); + /* Init each slice only once — both channels share clkdiv/wrap */ + if (!(motorSliceInitMask & (1u << slice))) { + pwm_config cfg = pwm_get_default_config(); + pwm_config_set_clkdiv(&cfg, clkdiv); + pwm_config_set_wrap(&cfg, MOTOR_PWM_WRAP); + pwm_init(slice, &cfg, false); + motorSliceInitMask |= (1u << slice); + } + pwm_set_gpio_level(gpio, MOTOR_MIN_US); + pwm_set_enabled(slice, true); + motorPwmPins[motorIdx] = (uint8_t)gpio; + } + motorIdx++; + + } else { /* SLICE_AS_SERVO */ + if (servoIdx >= RP2350_MAX_SERVOS) { + continue; /* silently skip: more pins than servo slots */ + } + gpio_set_function(gpio, GPIO_FUNC_PWM); + uint slice = pwm_gpio_to_slice_num(gpio); + /* Init each slice only once — both channels share clkdiv/wrap */ + if (!(servoSliceInitMask & (1u << slice))) { + pwm_config cfg = pwm_get_default_config(); + pwm_config_set_clkdiv(&cfg, clkdiv); + pwm_config_set_wrap(&cfg, SERVO_PWM_WRAP); + pwm_init(slice, &cfg, false); + servoSliceInitMask |= (1u << slice); + } + pwm_set_gpio_level(gpio, SERVO_DEFAULT_US); /* center pulse before enabling */ + pwm_set_enabled(slice, true); + servoHwPins[servoIdx++] = (uint8_t)gpio; + } + } + + /* ── Resolve timerHardware usageFlags ────────────────────────────── */ + /* STM32's pwm_mapping.c updates usageFlags after resolving AUTO so */ + /* that MSP2_INAV_OUTPUT_MAPPING_EXT2 reports the actual assignment. */ + /* Do the same here: replace AUTO with the resolved MOTOR or SERVO */ + /* flag so the configurator displays outputs in the correct order. */ + for (int i = 0; i < timerHardwareCount; i++) { + uint8_t sid = timer2id(timerHardware[i].tim); + if (sid >= HARDWARE_TIMER_DEFINITION_COUNT) { + continue; + } + if (sliceAssign[sid] == SLICE_AS_MOTOR) { + timerHardware[i].usageFlags = TIM_USE_MOTOR; + } else if (sliceAssign[sid] == SLICE_AS_SERVO) { + timerHardware[i].usageFlags = TIM_USE_SERVO; + } + } + + /* ── Commit counts ────────────────────────────────────────────────── */ + + if (dshot) { + dshotMotorCount = motorIdx; + dshotInitialized = true; + } else { + motorPwmCount = (uint8_t)motorIdx; + motorPwmInitialized = true; + } + servoCount = (uint8_t)servoIdx; + servoInitialized = true; + + return true; +} + +/* ── ESC update frequency ────────────────────────────────────────────────── */ + +uint32_t getEscUpdateFrequency(void) +{ + switch (initProtocol) { + case PWM_TYPE_DSHOT600: return 16000; + case PWM_TYPE_DSHOT300: return 8000; + case PWM_TYPE_DSHOT150: return 4000; + default: return 400; + } +} + +/* ── Init error reporting ────────────────────────────────────────────────── */ + +pwmInitError_e getPwmInitError(void) +{ + return rp2350PwmError; +} + +const char *getPwmInitErrorMessage(void) +{ + static const char *const msgs[] = { + [PWM_INIT_ERROR_NONE] = "No error", + [PWM_INIT_ERROR_TOO_MANY_MOTORS] = "Too many motors", + [PWM_INIT_ERROR_TOO_MANY_SERVOS] = "Too many servos", + [PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS] = "Not enough motor outputs", + [PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS] = "Not enough servo outputs", + [PWM_INIT_ERROR_TIMER_INIT_FAILED] = "Motor init failed", + }; + if ((size_t)rp2350PwmError >= ARRAYLEN(msgs) || !msgs[rp2350PwmError]) { + return "Unknown error"; + } + return msgs[rp2350PwmError]; +} + +/* ── Servo output ────────────────────────────────────────────────────────── */ + +void pwmWriteServo(uint8_t index, uint16_t value) +{ + if (!servoInitialized || index >= servoCount) { + return; + } + /* + * value=0 means "disarm / center" — output center pulse. + * Non-zero values are pulse widths in µs, clamped to servo range. + * At 1 µs/tick, pwm_set_gpio_level(pin, us) sets the pulse directly. + */ + uint16_t us = (value == 0) ? SERVO_DEFAULT_US + : (uint16_t)constrain(value, SERVO_MIN_US, SERVO_MAX_US); + pwm_set_gpio_level(servoHwPins[index], us); +} + +/* ── Beeper stubs (hardware not yet implemented) ─────────────────────────── */ + +void pwmWriteBeeper(bool onoffBeep) +{ + UNUSED(onoffBeep); +} + +void beeperPwmInit(ioTag_t tag, uint16_t frequency) +{ + UNUSED(tag); + UNUSED(frequency); +} + +#endif /* RP2350 */ diff --git a/src/main/drivers/serial_uart_rp2350.c b/src/main/drivers/serial_uart_rp2350.c new file mode 100644 index 00000000000..7cb79d23263 --- /dev/null +++ b/src/main/drivers/serial_uart_rp2350.c @@ -0,0 +1,398 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * RP2350 hardware UART driver for INAV — Milestone 6 + * + * Maps INAV serial ports to RP2350 hardware UARTs: + * UART1 (INAV) → uart0 (RP2350 UART0) + * UART2 (INAV) → uart1 (RP2350 UART1) + * + * Pin assignments are defined in target.h: + * UART1_TX_PIN / UART1_RX_PIN + * UART2_TX_PIN / UART2_RX_PIN + * + * RX is interrupt-driven (IRQ on FIFO not-empty). + * TX is interrupt-driven (IRQ on FIFO not-full, enabled on first write). + * + * Signal inversion (e.g. SBUS) is done in the GPIO controller via + * gpio_set_inover() — no external inverter circuit required. + */ + +#include "platform.h" + +#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) + +#include +#include + +#include "build/build_config.h" + +#include "common/utils.h" + +#include "drivers/io.h" +#include "drivers/serial.h" +#include "drivers/serial_uart.h" +#include "drivers/serial_uart_impl.h" + +#include "hardware/gpio.h" +#include "hardware/irq.h" +#include "hardware/uart.h" + +#define RP2350_UART_RX_BUFFER_SIZE 256 +#define RP2350_UART_TX_BUFFER_SIZE 256 + +/* Convert INAV ioTag_t to RP2350 raw GPIO number. */ +static inline uint ioTagToGpioNum(ioTag_t tag) +{ + return (uint)(DEFIO_TAG_GPIOID(tag) * 16 + DEFIO_TAG_PIN(tag)); +} + +/* + * Per-UART device state. + * + * uartPort_t is the first member so that a pointer to this struct is also + * a valid pointer to uartPort_t (and, by extension, serialPort_t), satisfying + * C99 §6.7.2.1 (first-member address rule). The vtable functions receive + * serialPort_t * and cast directly to rp2350UartDevice_t *. + */ +typedef struct { + uartPort_t port; + uart_inst_t *dev; + uint tx_pin; + uint rx_pin; + volatile uint8_t rxBuffer[RP2350_UART_RX_BUFFER_SIZE]; + volatile uint8_t txBuffer[RP2350_UART_TX_BUFFER_SIZE]; +} rp2350UartDevice_t; + +/* ── Forward declarations ────────────────────────────────────────────────── */ + +static void rp2350UartWrite(serialPort_t *instance, uint8_t ch); +static uint32_t rp2350UartTotalRxBytesWaiting(const serialPort_t *instance); +static uint32_t rp2350UartTotalTxBytesFree(const serialPort_t *instance); +static uint8_t rp2350UartRead(serialPort_t *instance); +static void rp2350UartSetBaudRate(serialPort_t *s, uint32_t baudRate); +static bool rp2350UartIsTransmitBufferEmpty(const serialPort_t *s); +static void rp2350UartSetMode(serialPort_t *instance, portMode_t mode); +static void rp2350UartSetOptions(serialPort_t *instance, portOptions_t options); + +/* Single shared vtable — identical for UART0 and UART1 */ +static const struct serialPortVTable rp2350UartVTable = { + .serialWrite = rp2350UartWrite, + .serialTotalRxWaiting = rp2350UartTotalRxBytesWaiting, + .serialTotalTxFree = rp2350UartTotalTxBytesFree, + .serialRead = rp2350UartRead, + .serialSetBaudRate = rp2350UartSetBaudRate, + .isSerialTransmitBufferEmpty = rp2350UartIsTransmitBufferEmpty, + .setMode = rp2350UartSetMode, + .setOptions = rp2350UartSetOptions, + .isConnected = NULL, + .writeBuf = NULL, + .beginWrite = NULL, + .endWrite = NULL, + .isIdle = NULL, +}; + +/* ── Hardware configure ──────────────────────────────────────────────────── */ + +static void rp2350UartHwConfigure(rp2350UartDevice_t *s) +{ + portOptions_t options = s->port.port.options; + uart_parity_t parity = (options & SERIAL_PARITY_EVEN) ? UART_PARITY_EVEN + : UART_PARITY_NONE; + uint stop_bits = (options & SERIAL_STOPBITS_2) ? 2 : 1; + + uart_set_baudrate(s->dev, s->port.port.baudRate); + uart_set_format(s->dev, 8, stop_bits, parity); + + /* + * RP2350 GPIO signal inversion — replaces the external inverter circuit + * that STM32 targets require for SBUS (100000 baud, 8E2, inverted). + */ + if (options & SERIAL_INVERTED) { + gpio_set_inover(s->rx_pin, GPIO_OVERRIDE_INVERT); + gpio_set_outover(s->tx_pin, GPIO_OVERRIDE_INVERT); + } else { + gpio_set_inover(s->rx_pin, GPIO_OVERRIDE_NORMAL); + gpio_set_outover(s->tx_pin, GPIO_OVERRIDE_NORMAL); + } +} + +/* ── Shared IRQ handler ──────────────────────────────────────────────────── */ + +static void rp2350UartIrqHandler(rp2350UartDevice_t *s) +{ + /* RX: drain hardware FIFO into the software ring buffer */ + while (uart_is_readable(s->dev)) { + uint8_t ch = (uint8_t)uart_get_hw(s->dev)->dr; + if (s->port.port.rxCallback) { + s->port.port.rxCallback(ch, s->port.port.rxCallbackData); + } else { + s->port.port.rxBuffer[s->port.port.rxBufferHead] = ch; + s->port.port.rxBufferHead = + (s->port.port.rxBufferHead + 1) % s->port.port.rxBufferSize; + } + } + + /* TX: push from software ring buffer into hardware FIFO */ + while (uart_is_writable(s->dev)) { + if (s->port.port.txBufferTail != s->port.port.txBufferHead) { + uart_get_hw(s->dev)->dr = + s->port.port.txBuffer[s->port.port.txBufferTail]; + s->port.port.txBufferTail = + (s->port.port.txBufferTail + 1) % s->port.port.txBufferSize; + } else { + /* Buffer empty — disable TX interrupt until next write */ + uart_set_irqs_enabled(s->dev, + (s->port.port.mode & MODE_RX) != 0, + false); + break; + } + } +} + +/* ── UART1 (INAV) → RP2350 uart0 ────────────────────────────────────────── */ + +#ifdef USE_UART1 + +static rp2350UartDevice_t uart0Device; + +static void uart0IrqHandler(void) +{ + rp2350UartIrqHandler(&uart0Device); +} + +uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + rp2350UartDevice_t *s = &uart0Device; + + s->dev = uart0; + s->tx_pin = ioTagToGpioNum(IO_TAG(UART1_TX_PIN)); + s->rx_pin = ioTagToGpioNum(IO_TAG(UART1_RX_PIN)); + + s->port.port.vTable = &rp2350UartVTable; + s->port.port.baudRate = baudRate; + s->port.port.mode = mode; + s->port.port.options = options; + s->port.port.rxBuffer = s->rxBuffer; + s->port.port.txBuffer = s->txBuffer; + s->port.port.rxBufferSize = sizeof(s->rxBuffer); + s->port.port.txBufferSize = sizeof(s->txBuffer); + s->port.port.rxBufferHead = 0; + s->port.port.rxBufferTail = 0; + s->port.port.txBufferHead = 0; + s->port.port.txBufferTail = 0; + + uart_init(uart0, baudRate); + if (mode & MODE_TX) { gpio_set_function(s->tx_pin, GPIO_FUNC_UART); } + if (mode & MODE_RX) { gpio_set_function(s->rx_pin, GPIO_FUNC_UART); } + + rp2350UartHwConfigure(s); + + irq_set_exclusive_handler(UART0_IRQ, uart0IrqHandler); + irq_set_enabled(UART0_IRQ, true); + + /* Enable RX interrupt; TX interrupt is enabled on demand by rp2350UartWrite() */ + uart_set_irqs_enabled(uart0, (mode & MODE_RX) != 0, false); + + return &s->port; +} + +#endif /* USE_UART1 */ + +/* ── UART2 (INAV) → RP2350 uart1 ────────────────────────────────────────── */ + +#ifdef USE_UART2 + +static rp2350UartDevice_t uart1Device; + +static void uart1IrqHandler(void) +{ + rp2350UartIrqHandler(&uart1Device); +} + +uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + rp2350UartDevice_t *s = &uart1Device; + + s->dev = uart1; + s->tx_pin = ioTagToGpioNum(IO_TAG(UART2_TX_PIN)); + s->rx_pin = ioTagToGpioNum(IO_TAG(UART2_RX_PIN)); + + s->port.port.vTable = &rp2350UartVTable; + s->port.port.baudRate = baudRate; + s->port.port.mode = mode; + s->port.port.options = options; + s->port.port.rxBuffer = s->rxBuffer; + s->port.port.txBuffer = s->txBuffer; + s->port.port.rxBufferSize = sizeof(s->rxBuffer); + s->port.port.txBufferSize = sizeof(s->txBuffer); + s->port.port.rxBufferHead = 0; + s->port.port.rxBufferTail = 0; + s->port.port.txBufferHead = 0; + s->port.port.txBufferTail = 0; + + uart_init(uart1, baudRate); + if (mode & MODE_TX) { gpio_set_function(s->tx_pin, GPIO_FUNC_UART); } + if (mode & MODE_RX) { gpio_set_function(s->rx_pin, GPIO_FUNC_UART); } + + rp2350UartHwConfigure(s); + + irq_set_exclusive_handler(UART1_IRQ, uart1IrqHandler); + irq_set_enabled(UART1_IRQ, true); + + uart_set_irqs_enabled(uart1, (mode & MODE_RX) != 0, false); + + return &s->port; +} + +#endif /* USE_UART2 */ + +/* ── Vtable implementations ──────────────────────────────────────────────── */ + +static void rp2350UartWrite(serialPort_t *instance, uint8_t ch) +{ + rp2350UartDevice_t *s = (rp2350UartDevice_t *)instance; + + s->port.port.txBuffer[s->port.port.txBufferHead] = ch; + s->port.port.txBufferHead = + (s->port.port.txBufferHead + 1) % s->port.port.txBufferSize; + + /* Enable TX FIFO-empty interrupt to drain the ring buffer */ + uart_set_irqs_enabled(s->dev, + (s->port.port.mode & MODE_RX) != 0, + true); +} + +static uint32_t rp2350UartTotalRxBytesWaiting(const serialPort_t *instance) +{ + const rp2350UartDevice_t *s = (const rp2350UartDevice_t *)instance; + if (s->port.port.rxBufferHead >= s->port.port.rxBufferTail) { + return s->port.port.rxBufferHead - s->port.port.rxBufferTail; + } + return s->port.port.rxBufferSize + s->port.port.rxBufferHead + - s->port.port.rxBufferTail; +} + +static uint32_t rp2350UartTotalTxBytesFree(const serialPort_t *instance) +{ + const rp2350UartDevice_t *s = (const rp2350UartDevice_t *)instance; + uint32_t bytesUsed; + if (s->port.port.txBufferHead >= s->port.port.txBufferTail) { + bytesUsed = s->port.port.txBufferHead - s->port.port.txBufferTail; + } else { + bytesUsed = s->port.port.txBufferSize + s->port.port.txBufferHead + - s->port.port.txBufferTail; + } + return (s->port.port.txBufferSize - 1) - bytesUsed; +} + +static uint8_t rp2350UartRead(serialPort_t *instance) +{ + rp2350UartDevice_t *s = (rp2350UartDevice_t *)instance; + uint8_t ch = s->port.port.rxBuffer[s->port.port.rxBufferTail]; + s->port.port.rxBufferTail = + (s->port.port.rxBufferTail + 1) % s->port.port.rxBufferSize; + return ch; +} + +static void rp2350UartSetBaudRate(serialPort_t *instance, uint32_t baudRate) +{ + rp2350UartDevice_t *s = (rp2350UartDevice_t *)instance; + s->port.port.baudRate = baudRate; + rp2350UartHwConfigure(s); +} + +static bool rp2350UartIsTransmitBufferEmpty(const serialPort_t *instance) +{ + const rp2350UartDevice_t *s = (const rp2350UartDevice_t *)instance; + return s->port.port.txBufferTail == s->port.port.txBufferHead; +} + +static void rp2350UartSetMode(serialPort_t *instance, portMode_t mode) +{ + rp2350UartDevice_t *s = (rp2350UartDevice_t *)instance; + s->port.port.mode = mode; + uart_set_irqs_enabled(s->dev, + (mode & MODE_RX) != 0, + !rp2350UartIsTransmitBufferEmpty(instance)); +} + +static void rp2350UartSetOptions(serialPort_t *instance, portOptions_t options) +{ + rp2350UartDevice_t *s = (rp2350UartDevice_t *)instance; + s->port.port.options = options; + rp2350UartHwConfigure(s); +} + +/* ── Stubs required by serial_uart.h / pwm_mapping.c ────────────────────── */ + +void uartGetPortPins(UARTDevice_e device, serialPortPins_t *pins) +{ + switch (device) { +#ifdef USE_UART1 + case UARTDEV_1: + pins->txPin = IO_TAG(UART1_TX_PIN); + pins->rxPin = IO_TAG(UART1_RX_PIN); + break; +#endif +#ifdef USE_UART2 + case UARTDEV_2: + pins->txPin = IO_TAG(UART2_TX_PIN); + pins->rxPin = IO_TAG(UART2_RX_PIN); + break; +#endif +#ifdef USE_UART3 + case UARTDEV_3: + pins->txPin = IO_TAG(UART3_TX_PIN); + pins->rxPin = IO_TAG(UART3_RX_PIN); + break; +#endif +#ifdef USE_UART4 + case UARTDEV_4: + pins->txPin = IO_TAG(UART4_TX_PIN); + pins->rxPin = IO_TAG(UART4_RX_PIN); + break; +#endif + default: + pins->txPin = IO_TAG(NONE); + pins->rxPin = IO_TAG(NONE); + break; + } +} + +void uartClearIdleFlag(uartPort_t *s) +{ + /* PL011 UART clears the idle flag automatically — nothing to do */ + UNUSED(s); +} + +/* + * uartVTable[] — required by serial_uart_impl.h's extern declaration. + * The RP2350 UART ports use rp2350UartVTable instead; this symbol exists + * only to satisfy the linker. + */ +const struct serialPortVTable uartVTable[1] = { { 0 } }; + +#endif /* USE_UART1 || USE_UART2 || USE_UART3 || USE_UART4 */ diff --git a/src/main/drivers/serial_usb_vcp_rp2350.c b/src/main/drivers/serial_usb_vcp_rp2350.c new file mode 100644 index 00000000000..5d32229a4ef --- /dev/null +++ b/src/main/drivers/serial_usb_vcp_rp2350.c @@ -0,0 +1,225 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * RP2350 USB VCP serial driver for INAV — Milestone 4 + * + * Implements INAV's serialPort_t vtable using TinyUSB CDC class. + * TinyUSB is initialized in systemInit() via tusb_init(); background USB + * event processing is driven by pico_stdio_usb's 1ms repeating alarm. + */ + +#include +#include + +#include "platform.h" + +#ifdef USE_VCP + +#include "build/build_config.h" + +#include "common/utils.h" +#include "drivers/time.h" + +#include "serial.h" +#include "serial_usb_vcp.h" + +#include "tusb.h" + +#define USB_TIMEOUT 50 + +static vcpPort_t vcpPort; + +static void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate) +{ + UNUSED(instance); + UNUSED(baudRate); +} + +static void usbVcpSetMode(serialPort_t *instance, portMode_t mode) +{ + UNUSED(instance); + UNUSED(mode); +} + +static void usbVcpSetOptions(serialPort_t *instance, portOptions_t options) +{ + UNUSED(instance); + UNUSED(options); +} + +static bool isUsbVcpTransmitBufferEmpty(const serialPort_t *instance) +{ + UNUSED(instance); + return true; +} + +static uint32_t usbVcpAvailable(const serialPort_t *instance) +{ + UNUSED(instance); + tud_task(); + return tud_cdc_available(); +} + +static uint8_t usbVcpRead(serialPort_t *instance) +{ + UNUSED(instance); + // Callers must check serialRxBytesWaiting() > 0 before calling serialRead(). + // Do not spin here — spinning would block the cooperative scheduler. + uint8_t ch = 0; + tud_cdc_read(&ch, 1); + return ch; +} + +static bool usbVcpIsConnected(const serialPort_t *instance) +{ + (void)instance; + return tud_cdc_connected(); +} + +static void usbVcpWriteBuf(serialPort_t *instance, const void *data, int count) +{ + UNUSED(instance); + + if (!usbVcpIsConnected(instance)) { + return; + } + + uint32_t start = millis(); + const uint8_t *p = data; + while (count > 0) { + uint32_t written = tud_cdc_write(p, count); + if (written > 0) { + count -= written; + p += written; + } + tud_cdc_write_flush(); + tud_task(); + if (millis() - start > USB_TIMEOUT) { + break; + } + } +} + +static bool usbVcpFlush(vcpPort_t *port) +{ + uint32_t count = port->txAt; + port->txAt = 0; + + if (count == 0) { + return true; + } + + if (!tud_cdc_connected()) { + return false; + } + + uint32_t start = millis(); + uint8_t *p = port->txBuf; + while (count > 0) { + uint32_t written = tud_cdc_write(p, count); + if (written > 0) { + count -= written; + p += written; + } + tud_cdc_write_flush(); + tud_task(); + if (millis() - start > USB_TIMEOUT) { + break; + } + } + return count == 0; +} + +static void usbVcpWrite(serialPort_t *instance, uint8_t c) +{ + vcpPort_t *port = container_of(instance, vcpPort_t, port); + + port->txBuf[port->txAt++] = c; + if (!port->buffering || port->txAt >= ARRAYLEN(port->txBuf)) { + usbVcpFlush(port); + } +} + +static void usbVcpBeginWrite(serialPort_t *instance) +{ + vcpPort_t *port = container_of(instance, vcpPort_t, port); + port->buffering = true; +} + +static uint32_t usbTxBytesFree(const serialPort_t *instance) +{ + UNUSED(instance); + return tud_cdc_write_available(); +} + +static void usbVcpEndWrite(serialPort_t *instance) +{ + vcpPort_t *port = container_of(instance, vcpPort_t, port); + port->buffering = false; + usbVcpFlush(port); +} + +static const struct serialPortVTable usbVTable[] = { + { + .serialWrite = usbVcpWrite, + .serialTotalRxWaiting = usbVcpAvailable, + .serialTotalTxFree = usbTxBytesFree, + .serialRead = usbVcpRead, + .serialSetBaudRate = usbVcpSetBaudRate, + .isSerialTransmitBufferEmpty = isUsbVcpTransmitBufferEmpty, + .setMode = usbVcpSetMode, + .setOptions = usbVcpSetOptions, + .isConnected = usbVcpIsConnected, + .writeBuf = usbVcpWriteBuf, + .beginWrite = usbVcpBeginWrite, + .endWrite = usbVcpEndWrite, + .isIdle = NULL, + } +}; + +void usbVcpInitHardware(void) +{ + // tusb_init() is called in systemInit() before fc_init(). + // tud_task() is driven by pico_stdio_usb's 1ms repeating alarm. + // Nothing additional needed here. +} + +serialPort_t *usbVcpOpen(void) +{ + vcpPort_t *s = &vcpPort; + s->port.vTable = usbVTable; + return (serialPort_t *)s; +} + +uint32_t usbVcpGetBaudRate(serialPort_t *instance) +{ + UNUSED(instance); + + cdc_line_coding_t coding; + tud_cdc_get_line_coding(&coding); + return coding.bit_rate; +} + +#endif // USE_VCP diff --git a/src/main/drivers/system_rp2350.c b/src/main/drivers/system_rp2350.c new file mode 100644 index 00000000000..4195cce1a88 --- /dev/null +++ b/src/main/drivers/system_rp2350.c @@ -0,0 +1,280 @@ +/* + * RP2350 system functions for INAV + * + * Processor-level implementations of timing, reset, system init, and + * CMSIS DSP stubs shared by all RP2350 boards. + * Analogous to drivers/system_stm32f7xx.c on F7 targets. + */ + +#include +#include +#include +#include + +#include + +#include "arm_math.h" +#include "common/time.h" +#include "common/utils.h" +#include "drivers/system.h" +#include "drivers/persistent.h" + +#include "hardware/clocks.h" +#include "hardware/gpio.h" +#include "hardware/timer.h" +#include "hardware/watchdog.h" +#include "hardware/structs/m33.h" +#include "pico/stdlib.h" +#include "pico/time.h" +#include "pico/unique_id.h" +#include "pico/bootrom.h" +#include "pico/runtime_init.h" +#include "tusb.h" + +// SystemCoreClock — updated by systemInit from SDK clock tree +uint32_t SystemCoreClock = 192000000; + +// ── Pre-init diagnostic blinks (run inside runtime_run_initializers) ────────── +// Enable by defining RP2350_DIAG_BLINK at compile time (e.g. in CMakeLists.txt). +// When active, blinks the onboard LED during early boot so a debugger-less board +// can show how far initialisation reached: +// 1 blink → "00150": after EARLY_RESETS — GPIO/SIO accessible +// 2 blinks → "00650": after POST_CLOCK_RESETS — clocks, coprocessors, aeabi done +// If neither fires, the crash is in BSS/data copy, bootrom_reset, or early_resets. +#ifdef RP2350_DIAG_BLINK + +#define DIAG_LED_PIN 25 + +static void diagRawBlink(int n) +{ + // gpio_init is safe after EARLY_RESETS ("00100") releases IOBANK0 + gpio_init(DIAG_LED_PIN); + gpio_set_dir(DIAG_LED_PIN, GPIO_OUT); + for (int i = 0; i < n; i++) { + gpio_put(DIAG_LED_PIN, 1); + busy_wait_us_32(200000); // 200 ms — no sleep_ms needed (timer always-on) + gpio_put(DIAG_LED_PIN, 0); + busy_wait_us_32(200000); + } + busy_wait_us_32(600000); // gap between groups +} + +static void diagPreInit_postEarlyResets(void) { diagRawBlink(1); } +PICO_RUNTIME_INIT_FUNC_RUNTIME(diagPreInit_postEarlyResets, "00150"); + +static void diagPreInit_postClocks(void) { diagRawBlink(2); } +PICO_RUNTIME_INIT_FUNC_RUNTIME(diagPreInit_postClocks, "00650"); + +#endif // RP2350_DIAG_BLINK + +// DWT cycle counter — Cortex-M33 Data Watchpoint and Trace +#define DWT_CTRL (m33_hw->dwt_ctrl) +#define DWT_CYCCNT (m33_hw->dwt_cyccnt) +#define DEMCR (m33_hw->demcr) + +#define DWT_CTRL_CYCCNTENA_Msk (1UL << 0) +#define DEMCR_TRCENA_Msk (1UL << 24) + +// Called from crt0.S as part of SDK runtime init +void SystemInit(void) +{ + // Enable DWT cycle counter + DEMCR |= DEMCR_TRCENA_Msk; + DWT_CYCCNT = 0; + DWT_CTRL |= DWT_CTRL_CYCCNTENA_Msk; +} + +static bool usb_task_timer_cb(repeating_timer_t *rt) +{ + (void)rt; + tud_task(); + return true; +} + +static repeating_timer_t usb_task_timer; + +void systemInit(void) +{ + persistentObjectInit(); + + // Raise sys clock from SDK default (150 MHz) to 192 MHz. + // The USB PLL is independent (clk_usb stays at 48 MHz from pll_usb) so + // TinyUSB CDC is unaffected. The hardware timer (clk_timer, derived from + // clk_ref at 12 MHz) is also unaffected, so micros() stays accurate. + // Must be called before tusb_init() / stdio_init_all() so those see the + // final clock rate. + set_sys_clock_khz(192000, true); + + // SDK runtime already initialized clocks, GPIO, etc. via crt0 → runtime_init + SystemCoreClock = clock_get_hz(clk_sys); + + // tusb_init() must be called before stdio_init_all() because + // LIB_TINYUSB_DEVICE=1 (from CFG_TUD_ENABLED in tusb_config.h) causes + // PICO_STDIO_USB_ENABLE_TINYUSB_INIT=0, so stdio_usb_init() skips it. + tusb_init(); + + // Drive USB regardless of scheduler state: fire tud_task() every 1 ms + // from a hardware alarm (same approach pico_stdio_usb uses internally). + if (!add_repeating_timer_ms(-1, usb_task_timer_cb, NULL, &usb_task_timer)) { + // Alarm pool exhausted — USB CDC will not receive background servicing. + // Nothing useful to do here; continue boot without functional USB. + } + + stdio_init_all(); +} + +// --- Timing functions --- + +timeUs_t micros(void) +{ + return (timeUs_t)time_us_32(); +} + +uint64_t microsISR(void) +{ + return time_us_64(); +} + +uint32_t millis(void) +{ + return (uint32_t)(time_us_64() / 1000ULL); +} + +void delayNanos(timeDelta_t ns) +{ + if (ns <= 0) return; + busy_wait_us_32(((uint32_t)ns + 999U) / 1000U); +} + +void delayMicroseconds(timeUs_t us) +{ + busy_wait_us_32((uint32_t)us); +} + +void delay(timeMs_t ms) +{ + busy_wait_ms((uint32_t)ms); +} + +uint32_t getCycleCounter(void) +{ + return DWT_CYCCNT; +} + +// --- Reset functions --- + +void systemReset(void) +{ + watchdog_reboot(0, 0, 0); + while (1) {} +} + +void systemResetRequest(uint32_t requestId) +{ + persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, requestId); + systemReset(); +} + +void systemResetToBootloader(void) +{ + rom_reset_usb_boot(0, 0); + while (1) {} +} + +// --- Newlib syscall stubs (required by libc_nano) --- + +#include + +__attribute__((used)) int _fstat(int fd, struct stat *buf) +{ + (void)fd; + (void)buf; + return -1; +} + +__attribute__((used)) int _isatty(int fd) +{ + (void)fd; + return 1; +} + +// --- Unique ID --- + +void getUniqueId(uint8_t *id) +{ + pico_unique_board_id_t board_id; + pico_get_unique_board_id(&board_id); + // INAV expects 12 bytes (U_ID_0/1/2 = 3x uint32_t). + // Pico has 8 bytes — copy and pad with zeros. + memcpy(id, board_id.id, 8); + memset(id + 8, 0, 4); +} + +// --- CMSIS DSP stubs --- +// +// The bundled CMSIS DSP library predates ARMv8-M and conflicts with the newer +// CMSIS Core headers required by the Pico SDK. INAV common code that calls +// these functions is compiled for RP2350, so we provide empty stubs here. +// Analogous to SITL's stubs in target/SITL/target.c. + +arm_status arm_rfft_fast_init_f32(arm_rfft_fast_instance_f32 *S, uint16_t fftLen) +{ + UNUSED(S); + UNUSED(fftLen); + return ARM_MATH_SUCCESS; +} + +void arm_cfft_radix8by4_f32(arm_cfft_instance_f32 *S, float32_t *p1) +{ + UNUSED(S); + UNUSED(p1); +} + +void arm_bitreversal_32(uint32_t *pSrc, const uint16_t bitRevLen, + const uint16_t *pBitRevTable) +{ + UNUSED(pSrc); + UNUSED(bitRevLen); + UNUSED(pBitRevTable); +} + +void stage_rfft_f32(arm_rfft_fast_instance_f32 *S, float32_t *p, float32_t *pOut) +{ + UNUSED(S); + UNUSED(p); + UNUSED(pOut); +} + +void arm_cmplx_mag_f32(float32_t *pSrc, float32_t *pDst, uint32_t numSamples) +{ + UNUSED(pSrc); + UNUSED(pDst); + UNUSED(numSamples); +} + +void arm_mult_f32(float32_t *pSrcA, float32_t *pSrcB, + float32_t *pDst, uint32_t blockSize) +{ + UNUSED(pSrcA); + UNUSED(pSrcB); + UNUSED(pDst); + UNUSED(blockSize); +} + +void arm_sub_f32(float32_t *pSrcA, float32_t *pSrcB, + float32_t *pDst, uint32_t blockSize) +{ + UNUSED(pSrcA); + UNUSED(pSrcB); + UNUSED(pDst); + UNUSED(blockSize); +} + +void arm_scale_f32(float32_t *pSrc, float32_t scale, + float32_t *pDst, uint32_t blockSize) +{ + UNUSED(pSrc); + UNUSED(scale); + UNUSED(pDst); + UNUSED(blockSize); +} diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index d87e0400d52..4e806cee701 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -46,6 +46,11 @@ typedef uint32_t timCCR_t; typedef uint32_t timCCER_t; typedef uint32_t timSR_t; typedef uint32_t timCNT_t; +#elif defined(RP2350) +typedef uint32_t timCCR_t; +typedef uint32_t timCCER_t; +typedef uint32_t timSR_t; +typedef uint32_t timCNT_t; #else #error "Unknown CPU defined" #endif @@ -60,6 +65,8 @@ typedef uint32_t timCNT_t; #define HARDWARE_TIMER_DEFINITION_COUNT 15 #elif defined(SITL_BUILD) #define HARDWARE_TIMER_DEFINITION_COUNT 0 +#elif defined(RP2350) +#define HARDWARE_TIMER_DEFINITION_COUNT 5 #else #error "Unknown CPU defined" #endif diff --git a/src/main/drivers/timer_def.h b/src/main/drivers/timer_def.h index c5cdc820301..752af85b4f9 100644 --- a/src/main/drivers/timer_def.h +++ b/src/main/drivers/timer_def.h @@ -108,6 +108,21 @@ #elif defined(AT32F43x) #include "timer_def_at32f43x.h" #elif defined(SITL_BUILD) +#elif defined(RP2350) +/* + * RP2350 DEF_TIM — same 6-parameter signature as STM32 so existing scripts + * and tooling that parse timerHardware[] tables work unchanged. + * + * Parameters: + * tim — PWM slice pointer macro (e.g. RP2350_PWM4), analogous to TIM4 + * ch — channel token: CH1 (= slice channel A) or CH2 (= slice channel B) + * pin — GPIO name in INAV port notation (e.g. PA8 for GP8, PB0 for GP16) + * usage — TIM_USE_* flags (typically TIM_USE_OUTPUT_AUTO) + * flags — accepted but unused on RP2350 (no N-channel outputs); pass 0 + * dmavar — accepted but unused on RP2350 (no DMA-driven PWM); pass 0 + */ +#define DEF_TIM(tim, ch, pin, usage, flags, dmavar) \ + { tim, IO_TAG(pin), DEF_TIM_CHNL_ ## ch, 0, 0, 0, usage, 0 } #else #error "Unknown CPU defined" #endif diff --git a/src/main/drivers/timer_rp2350.c b/src/main/drivers/timer_rp2350.c new file mode 100644 index 00000000000..a9f3551d47a --- /dev/null +++ b/src/main/drivers/timer_rp2350.c @@ -0,0 +1,77 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * RP2350 PWM slice group identifiers and timer utilities. + * + * Provides the per-slice TIM_TypeDef identity tokens used by timerHardware[] + * in each board's target.c. These are processor-specific: PWM slice numbers + * are determined by the RP2350 chip (slice = gpio / 2), not by any particular + * board layout. They therefore live in drivers/ rather than a target directory + * so future RP2350 boards can reuse them without duplication. + * + * Analogous to the TIM4/TIM5/… peripheral register structs on STM32 (which + * live in CMSIS headers, not in any target directory). Here the TIM_TypeDef + * instances contain no real register content — only their addresses matter, + * used as unique group identifiers by timer2id() and pwmMotorAndServoInit(). + * + * The TIM4/TIM5/TIM10 pointer macros and extern declarations are in + * target.h (board header) for now; when a second RP2350 board is added they + * should move to a shared drivers/timer_rp2350.h. + */ + +#include +#include + +#include + +#include "drivers/timer.h" + +/* + * One TIM_TypeDef instance per RP2350 PWM slice in use. + * slice = gpio / 2 (RP2350 hardware rule). + * Both channels (A = even GPIO, B = odd GPIO) on a slice share clkdiv/wrap, + * so they must run at the same update rate — same constraint as STM32 timers. + */ +TIM_TypeDef rp2350Pwm4 = { NULL }; /* slice 4: GP8/GP9 (8/2 = 4) motors 1-2 */ +TIM_TypeDef rp2350Pwm5 = { NULL }; /* slice 5: GP10/GP11 (10/2 = 5) motors 3-4 */ +TIM_TypeDef rp2350Pwm6 = { NULL }; /* slice 6: GP12/GP13 (12/2 = 6) servos (dual-use UART3) */ +TIM_TypeDef rp2350Pwm7 = { NULL }; /* slice 7: GP14/GP15 (14/2 = 7) servos (dual-use UART4) */ +TIM_TypeDef rp2350Pwm10 = { NULL }; /* slice 10: GP20/GP21 (20/2 = 10) servos (dedicated) */ + +void timerInit(void) +{ + /* NOP — RP2350 PWM slices are configured by pwmMotorAndServoInit() */ +} + +/* Returns the 0-based slice index for use as a timerOverrides() array index. */ +uint8_t timer2id(const HAL_Timer_t *tim) +{ + if (tim == TIM4) return 0; + if (tim == TIM5) return 1; + if (tim == TIM6) return 2; + if (tim == TIM7) return 3; + if (tim == TIM10) return 4; + return (uint8_t)-1; +} diff --git a/src/main/drivers/uart_pio_rp2350.c b/src/main/drivers/uart_pio_rp2350.c new file mode 100644 index 00000000000..75517c9670b --- /dev/null +++ b/src/main/drivers/uart_pio_rp2350.c @@ -0,0 +1,503 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * RP2350 PIO software UART driver for INAV — Milestone 6 + * + * Implements UART3 and UART4 using PIO state machines on PIO1: + * + * UART3 (INAV) → PIO1 SM0 (TX) + SM1 (RX) — PIO1_IRQ0 + * UART4 (INAV) → PIO1 SM2 (TX) + SM3 (RX) — PIO1_IRQ1 + * + * PIO program budget (32 instructions per block): + * TX program: 4 instructions (shared by SM0 and SM2) + * RX program: 9 instructions (shared by SM1 and SM3) + * Total used: 13 of 32 — well within budget. + * + * Each SM has its own clock divider, so UART3 and UART4 can run at + * different baud rates simultaneously (e.g. 420000 baud CRSF + 57600 baud + * telemetry). + * + * PIO programs are pre-assembled from pico-examples/pio/uart_tx.pio and + * uart_rx.pio (BSD-3-Clause, copyright Raspberry Pi Trading Ltd). + * Embedding pre-assembled instruction arrays avoids a pioasm build step. + * + * RX FIFO data layout: the RX SM shifts in bits MSB-first, so each received + * byte lands in bits [31:24] of the 32-bit FIFO word. Read with >> 24. + * + * Signal inversion (SBUS) is done via gpio_set_inover/outover — no external + * inverter required. + * + * Pin assignments are defined in target.h: + * UART3_TX_PIN / UART3_RX_PIN + * UART4_TX_PIN / UART4_RX_PIN + */ + +#include "platform.h" + +#if defined(USE_UART3) || defined(USE_UART4) + +#include +#include + +#include "build/build_config.h" +#include "common/utils.h" + +#include "drivers/io.h" +#include "drivers/serial.h" +#include "drivers/serial_uart.h" +#include "drivers/serial_uart_impl.h" + +#include "hardware/clocks.h" +#include "hardware/gpio.h" +#include "hardware/irq.h" +#include "hardware/pio.h" + +/* ── Pre-assembled PIO programs ───────────────────────────────────────────── + * + * Source: pico-examples/pio/uart_tx.pio and uart_rx.pio + * Copyright (c) 2020 Raspberry Pi (Trading) Ltd. BSD-3-Clause. + */ + +/* uart_tx — 4 instructions, uses side-set on pin_tx ──────────────────────── */ +static const uint16_t uart_tx_instructions[] = { + 0x9fa0, // 0: pull block side 1 [7] — pull & idle high + 0xf727, // 1: set x, 7 side 0 [7] — start bit + 0x6001, // 2: out pins, 1 — data bit + 0x0642, // 3: jmp x--, 2 [6] — loop +}; +static const struct pio_program uart_tx_program = { + .instructions = uart_tx_instructions, + .length = 4, + .origin = -1, + .pio_version = 0, +#if PICO_PIO_VERSION > 0 + .used_gpio_ranges = 0x0, +#endif +}; + +/* uart_rx — 9 instructions ──────────────────────────────────────────────── */ +static const uint16_t uart_rx_instructions[] = { + 0x2020, // 0: wait 0 pin, 0 — wait for start bit + 0xea27, // 1: set x, 7 [10] — init bit counter + half-bit delay + 0x4001, // 2: in pins, 1 — sample bit + 0x0642, // 3: jmp x--, 2 [6] — loop 8 bits + 0x00c8, // 4: jmp pin, 8 — check stop bit + 0xc014, // 5: irq nowait 4 rel — signal framing error + 0x20a0, // 6: wait 1 pin, 0 — wait for line idle + 0x0000, // 7: jmp 0 — restart + 0x8020, // 8: push block — push byte to FIFO +}; +static const struct pio_program uart_rx_program = { + .instructions = uart_rx_instructions, + .length = 9, + .origin = -1, + .pio_version = 0, +#if PICO_PIO_VERSION > 0 + .used_gpio_ranges = 0x0, +#endif +}; + +/* ── Program init helpers ────────────────────────────────────────────────── */ + +/* Convert INAV ioTag_t to RP2350 raw GPIO number. */ +static inline uint ioTagToGpioNum(ioTag_t tag) +{ + return (uint)(DEFIO_TAG_GPIOID(tag) * 16 + DEFIO_TAG_PIN(tag)); +} + +static void uart_tx_program_init(PIO pio, uint sm, uint offset, uint pin, uint baud) +{ + pio_sm_set_pins_with_mask64(pio, sm, 1ull << pin, 1ull << pin); + pio_sm_set_pindirs_with_mask64(pio, sm, 1ull << pin, 1ull << pin); + pio_gpio_init(pio, pin); + + pio_sm_config c = pio_get_default_sm_config(); + sm_config_set_wrap(&c, offset + 0, offset + 3); + sm_config_set_sideset(&c, 2, true, false); + sm_config_set_out_shift(&c, true, false, 32); + sm_config_set_out_pins(&c, pin, 1); + sm_config_set_sideset_pins(&c, pin); + sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX); + float div = (float)clock_get_hz(clk_sys) / (8.0f * (float)baud); + sm_config_set_clkdiv(&c, div); + pio_sm_init(pio, sm, offset, &c); + pio_sm_set_enabled(pio, sm, true); +} + +static void uart_rx_program_init(PIO pio, uint sm, uint offset, uint pin, uint baud) +{ + pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, false); + pio_gpio_init(pio, pin); + gpio_pull_up(pin); + + pio_sm_config c = pio_get_default_sm_config(); + sm_config_set_wrap(&c, offset + 0, offset + 8); + sm_config_set_in_pins(&c, pin); + sm_config_set_jmp_pin(&c, pin); + sm_config_set_in_shift(&c, true, false, 32); + sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX); + float div = (float)clock_get_hz(clk_sys) / (8.0f * (float)baud); + sm_config_set_clkdiv(&c, div); + pio_sm_init(pio, sm, offset, &c); + pio_sm_set_enabled(pio, sm, true); +} + +/* ── Device struct ───────────────────────────────────────────────────────── */ + +/* + * piouartDevice_t — PIO UART port state. + * + * uartPort_t is the first member so that (piouartDevice_t *) ↔ (uartPort_t *) + * ↔ (serialPort_t *) casts are valid (C99 §6.7.2.1 first-member rule). + */ +typedef struct { + uartPort_t port; + uint sm_tx; /* state machine index for TX (0..3) */ + uint sm_rx; /* state machine index for RX (0..3) */ + uint tx_pin; + uint rx_pin; + int irq_index; /* 0 = PIO1_IRQ0, 1 = PIO1_IRQ1 */ + uint32_t rx_intr_bit; /* PIO_INTR_SMx_RXNEMPTY_BITS for sm_rx */ + uint32_t tx_intr_bit; /* PIO_INTR_SMx_TXNFULL_BITS for sm_tx */ + int tx_offset; /* pio_add_program offset for TX program */ + int rx_offset; /* pio_add_program offset for RX program */ + volatile uint8_t rxBuffer[256]; + volatile uint8_t txBuffer[256]; +} piouartDevice_t; + +/* ── Forward declarations ────────────────────────────────────────────────── */ + +static void pioUartWrite(serialPort_t *instance, uint8_t ch); +static uint32_t pioUartTotalRxBytesWaiting(const serialPort_t *instance); +static uint32_t pioUartTotalTxBytesFree(const serialPort_t *instance); +static uint8_t pioUartRead(serialPort_t *instance); +static void pioUartSetBaudRate(serialPort_t *s, uint32_t baudRate); +static bool pioUartIsTransmitBufferEmpty(const serialPort_t *s); +static void pioUartSetMode(serialPort_t *instance, portMode_t mode); +static void pioUartSetOptions(serialPort_t *instance, portOptions_t options); + +static const struct serialPortVTable pioUartVTable = { + .serialWrite = pioUartWrite, + .serialTotalRxWaiting = pioUartTotalRxBytesWaiting, + .serialTotalTxFree = pioUartTotalTxBytesFree, + .serialRead = pioUartRead, + .serialSetBaudRate = pioUartSetBaudRate, + .isSerialTransmitBufferEmpty = pioUartIsTransmitBufferEmpty, + .setMode = pioUartSetMode, + .setOptions = pioUartSetOptions, + .isConnected = NULL, + .writeBuf = NULL, + .beginWrite = NULL, + .endWrite = NULL, + .isIdle = NULL, +}; + +/* Program offsets — loaded once into PIO1, shared by both UARTs */ +static int txProgramOffset = -1; +static int rxProgramOffset = -1; + +/* Lookup tables for PIO interrupt register bits by SM index */ +static const uint32_t sm_rxnempty_bits[4] = { + PIO_INTR_SM0_RXNEMPTY_BITS, + PIO_INTR_SM1_RXNEMPTY_BITS, + PIO_INTR_SM2_RXNEMPTY_BITS, + PIO_INTR_SM3_RXNEMPTY_BITS, +}; +static const uint32_t sm_txnfull_bits[4] = { + PIO_INTR_SM0_TXNFULL_BITS, + PIO_INTR_SM1_TXNFULL_BITS, + PIO_INTR_SM2_TXNFULL_BITS, + PIO_INTR_SM3_TXNFULL_BITS, +}; + +/* ── Shared IRQ handler ──────────────────────────────────────────────────── */ + +static void piouartIrqHandler(piouartDevice_t *s) +{ + io_rw_32 *inte = s->irq_index == 0 ? &pio1->inte0 : &pio1->inte1; + io_ro_32 *ints = s->irq_index == 0 ? &pio1->ints0 : &pio1->ints1; + + /* RX: drain FIFO into ring buffer while not empty */ + if (*ints & s->rx_intr_bit) { + while (!pio_sm_is_rx_fifo_empty(pio1, s->sm_rx)) { + /* + * With shift_right=true and push_threshold=32, 8 bits shift into + * the top of the ISR so the byte sits in bits [31:24] — left- + * justified. Use >> 24 to extract. + */ + uint8_t ch = (uint8_t)(pio1->rxf[s->sm_rx] >> 24); + if (s->port.port.rxCallback) { + s->port.port.rxCallback(ch, s->port.port.rxCallbackData); + } else { + s->port.port.rxBuffer[s->port.port.rxBufferHead] = ch; + s->port.port.rxBufferHead = + (s->port.port.rxBufferHead + 1) % s->port.port.rxBufferSize; + } + } + } + + /* + * TX: push ring buffer bytes into PIO TX FIFO. + * + * We check *inte (enable register) rather than *ints because the TX + * FIFO-not-full condition is almost always true — using ints would fire + * on every IRQ entry even when there's nothing to send. + */ + if (*inte & s->tx_intr_bit) { + while (!pio_sm_is_tx_fifo_full(pio1, s->sm_tx)) { + if (s->port.port.txBufferTail != s->port.port.txBufferHead) { + /* PIO TX program reads the low 8 bits of the FIFO word */ + pio_sm_put(pio1, s->sm_tx, + s->port.port.txBuffer[s->port.port.txBufferTail]); + s->port.port.txBufferTail = + (s->port.port.txBufferTail + 1) % s->port.port.txBufferSize; + } else { + /* Buffer empty — disable TX interrupt until next write */ + pio_set_irqn_source_enabled(pio1, (uint)s->irq_index, + pio_get_tx_fifo_not_full_interrupt_source(s->sm_tx), false); + break; + } + } + } +} + +/* ── piouartInit — shared init for UART3 and UART4 ──────────────────────── */ + +/* + * piouartInit is NOT inside any #ifdef USE_UARTn guard so that it compiles + * whenever USE_UART3 or USE_UART4 (or both) are defined. Placing it inside + * the USE_UART3 guard would cause a linker error if only USE_UART4 is defined. + */ +static uartPort_t *piouartInit(piouartDevice_t *s, uint sm_tx, uint sm_rx, + uint tx_pin, uint rx_pin, int irq_index, + uint32_t baudRate, portMode_t mode, + portOptions_t options) +{ + s->sm_tx = sm_tx; + s->sm_rx = sm_rx; + s->tx_pin = tx_pin; + s->rx_pin = rx_pin; + s->irq_index = irq_index; + s->rx_intr_bit = sm_rxnempty_bits[sm_rx]; + s->tx_intr_bit = sm_txnfull_bits[sm_tx]; + + s->port.port.vTable = &pioUartVTable; + s->port.port.baudRate = baudRate; + s->port.port.mode = mode; + s->port.port.options = options; + s->port.port.rxBuffer = s->rxBuffer; + s->port.port.txBuffer = s->txBuffer; + s->port.port.rxBufferSize = sizeof(s->rxBuffer); + s->port.port.txBufferSize = sizeof(s->txBuffer); + s->port.port.rxBufferHead = 0; + s->port.port.rxBufferTail = 0; + s->port.port.txBufferHead = 0; + s->port.port.txBufferTail = 0; + + /* Load programs once — each subsequent call reuses the same offset */ + if (txProgramOffset < 0) { + txProgramOffset = pio_add_program(pio1, &uart_tx_program); + } + if (rxProgramOffset < 0) { + rxProgramOffset = pio_add_program(pio1, &uart_rx_program); + } + + uart_tx_program_init(pio1, sm_tx, (uint)txProgramOffset, tx_pin, baudRate); + uart_rx_program_init(pio1, sm_rx, (uint)rxProgramOffset, rx_pin, baudRate); + + /* + * GPIO signal inversion — replaces the external inverter that STM32 targets + * require for SBUS (100000 baud, 8E2, inverted). RP2350 can invert any GPIO + * input/output in hardware. + */ + if (options & SERIAL_INVERTED) { + gpio_set_inover(rx_pin, GPIO_OVERRIDE_INVERT); + gpio_set_outover(tx_pin, GPIO_OVERRIDE_INVERT); + } + + return &s->port; +} + +/* ── UART3 (INAV) → PIO1 SM0 (TX) + SM1 (RX) ───────────────────────────── */ + +#ifdef USE_UART3 + +static piouartDevice_t piouart0Device; + +static void pio1Irq0Handler(void) +{ + piouartIrqHandler(&piouart0Device); +} + +uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + uartPort_t *p = piouartInit(&piouart0Device, + 0 /* sm_tx */, 1 /* sm_rx */, + ioTagToGpioNum(IO_TAG(UART3_TX_PIN)), + ioTagToGpioNum(IO_TAG(UART3_RX_PIN)), + 0 /* irq_index = PIO1_IRQ0 */, + baudRate, mode, options); + + irq_set_exclusive_handler(PIO1_IRQ_0, pio1Irq0Handler); + irq_set_enabled(PIO1_IRQ_0, true); + + /* Enable RX interrupt; TX is enabled on demand in pioUartWrite() */ + if (mode & MODE_RX) { + pio_set_irqn_source_enabled(pio1, 0, + pio_get_rx_fifo_not_empty_interrupt_source(1 /* sm_rx */), true); + } + + return p; +} + +#endif /* USE_UART3 */ + +/* ── UART4 (INAV) → PIO1 SM2 (TX) + SM3 (RX) ───────────────────────────── */ + +#ifdef USE_UART4 + +static piouartDevice_t piouart1Device; + +static void pio1Irq1Handler(void) +{ + piouartIrqHandler(&piouart1Device); +} + +uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options) +{ + uartPort_t *p = piouartInit(&piouart1Device, + 2 /* sm_tx */, 3 /* sm_rx */, + ioTagToGpioNum(IO_TAG(UART4_TX_PIN)), + ioTagToGpioNum(IO_TAG(UART4_RX_PIN)), + 1 /* irq_index = PIO1_IRQ1 */, + baudRate, mode, options); + + irq_set_exclusive_handler(PIO1_IRQ_1, pio1Irq1Handler); + irq_set_enabled(PIO1_IRQ_1, true); + + if (mode & MODE_RX) { + pio_set_irqn_source_enabled(pio1, 1, + pio_get_rx_fifo_not_empty_interrupt_source(3 /* sm_rx */), true); + } + + return p; +} + +#endif /* USE_UART4 */ + +/* ── Vtable implementations ──────────────────────────────────────────────── */ + +static void pioUartWrite(serialPort_t *instance, uint8_t ch) +{ + piouartDevice_t *s = (piouartDevice_t *)instance; + + s->port.port.txBuffer[s->port.port.txBufferHead] = ch; + s->port.port.txBufferHead = + (s->port.port.txBufferHead + 1) % s->port.port.txBufferSize; + + pio_set_irqn_source_enabled(pio1, (uint)s->irq_index, + pio_get_tx_fifo_not_full_interrupt_source(s->sm_tx), true); +} + +static uint32_t pioUartTotalRxBytesWaiting(const serialPort_t *instance) +{ + const piouartDevice_t *s = (const piouartDevice_t *)instance; + if (s->port.port.rxBufferHead >= s->port.port.rxBufferTail) { + return s->port.port.rxBufferHead - s->port.port.rxBufferTail; + } + return s->port.port.rxBufferSize + s->port.port.rxBufferHead + - s->port.port.rxBufferTail; +} + +static uint32_t pioUartTotalTxBytesFree(const serialPort_t *instance) +{ + const piouartDevice_t *s = (const piouartDevice_t *)instance; + uint32_t bytesUsed; + if (s->port.port.txBufferHead >= s->port.port.txBufferTail) { + bytesUsed = s->port.port.txBufferHead - s->port.port.txBufferTail; + } else { + bytesUsed = s->port.port.txBufferSize + s->port.port.txBufferHead + - s->port.port.txBufferTail; + } + return (s->port.port.txBufferSize - 1) - bytesUsed; +} + +static uint8_t pioUartRead(serialPort_t *instance) +{ + piouartDevice_t *s = (piouartDevice_t *)instance; + uint8_t ch = s->port.port.rxBuffer[s->port.port.rxBufferTail]; + s->port.port.rxBufferTail = + (s->port.port.rxBufferTail + 1) % s->port.port.rxBufferSize; + return ch; +} + +static void pioUartSetBaudRate(serialPort_t *instance, uint32_t baudRate) +{ + piouartDevice_t *s = (piouartDevice_t *)instance; + s->port.port.baudRate = baudRate; + + /* + * Reinitialise both SMs with new clock divider. pio_sm_clear_fifos() is + * called internally by uart_tx/rx_program_init → pio_sm_init, so any bytes + * queued in the TX ring buffer but not yet pushed to the PIO FIFO will still + * be sent, but bytes already in the hardware FIFO are discarded. Callers + * that need a clean switch (e.g. GPS auto-baud) should drain the port first. + */ + pio_sm_set_enabled(pio1, s->sm_tx, false); + pio_sm_set_enabled(pio1, s->sm_rx, false); + uart_tx_program_init(pio1, s->sm_tx, (uint)txProgramOffset, s->tx_pin, baudRate); + uart_rx_program_init(pio1, s->sm_rx, (uint)rxProgramOffset, s->rx_pin, baudRate); +} + +static bool pioUartIsTransmitBufferEmpty(const serialPort_t *instance) +{ + const piouartDevice_t *s = (const piouartDevice_t *)instance; + return s->port.port.txBufferTail == s->port.port.txBufferHead; +} + +static void pioUartSetMode(serialPort_t *instance, portMode_t mode) +{ + piouartDevice_t *s = (piouartDevice_t *)instance; + s->port.port.mode = mode; + pio_set_irqn_source_enabled(pio1, (uint)s->irq_index, + pio_get_rx_fifo_not_empty_interrupt_source(s->sm_rx), + (mode & MODE_RX) != 0); +} + +static void pioUartSetOptions(serialPort_t *instance, portOptions_t options) +{ + piouartDevice_t *s = (piouartDevice_t *)instance; + s->port.port.options = options; + + if (options & SERIAL_INVERTED) { + gpio_set_inover(s->rx_pin, GPIO_OVERRIDE_INVERT); + gpio_set_outover(s->tx_pin, GPIO_OVERRIDE_INVERT); + } else { + gpio_set_inover(s->rx_pin, GPIO_OVERRIDE_NORMAL); + gpio_set_outover(s->tx_pin, GPIO_OVERRIDE_NORMAL); + } +} + +#endif /* USE_UART3 || USE_UART4 */ diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 6c60f08c6ed..a7cd48997e8 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4076,7 +4076,7 @@ static void cliStatus(char *cmdline) } } cliPrintLinefeed(); -#if !defined(SITL_BUILD) +#if !defined(SITL_BUILD) && !defined(RP2350) #if defined(AT32F43x) cliPrintLine("AT32 system clocks:"); crm_clocks_freq_type clocks; @@ -4131,19 +4131,19 @@ static void cliStatus(char *cmdline) #endif #ifdef USE_I2C const uint16_t i2cErrorCounter = i2cGetErrorCounter(); -#elif !defined(SITL_BUILD) +#elif !defined(SITL_BUILD) && !defined(RP2350) const uint16_t i2cErrorCounter = 0; #endif #ifdef STACK_CHECK cliPrintf("Stack used: %d, ", stackUsedSize()); #endif -#if !defined(SITL_BUILD) +#if !defined(SITL_BUILD) && !defined(RP2350) cliPrintLinef("Stack size: %d, Stack address: 0x%x, Heap available: %d", stackTotalSize(), stackHighMem(), memGetAvailableBytes()); cliPrintLinef("I2C Errors: %d, config size: %d, max available config: %d", i2cErrorCounter, getEEPROMConfigSize(), &__config_end - &__config_start); #endif -#if defined(USE_ADC) && !defined(SITL_BUILD) +#if defined(USE_ADC) && !defined(SITL_BUILD) && !defined(RP2350) static char * adcFunctions[] = { "BATTERY", "RSSI", "CURRENT", "AIRSPEED" }; cliPrintLine("ADC channel usage:"); for (int i = 0; i < ADC_FUNCTION_COUNT; i++) { diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 0cf6240771f..db53b4fa03f 100644 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -177,7 +177,7 @@ bool areSensorsCalibrating(void) return false; } -int16_t getAxisRcCommand(int16_t rawData, int16_t rate, int16_t deadband) +int16_t FAST_CODE getAxisRcCommand(int16_t rawData, int16_t rate, int16_t deadband) { int16_t stickDeflection = 0; @@ -383,17 +383,32 @@ static bool emergencyArmingIsEnabled(void) return emergencyArmingUpdate(IS_RC_MODE_ACTIVE(BOXARM), false) && emergencyArmingCanOverrideArmingDisabled(); } -static void processPilotAndFailSafeActions(float dT) +static RP2350_FAST_CODE void processPilotAndFailSafeActions(float dT) { if (failsafeShouldApplyControlInput()) { // Failsafe will apply rcCommand for us failsafeApplyControlInput(); } else { - // Compute ROLL PITCH and YAW command - rcCommand[ROLL] = getAxisRcCommand(rxGetChannelValue(ROLL), FLIGHT_MODE(MANUAL_MODE) ? currentControlProfile->manual.rcExpo8 : currentControlProfile->stabilized.rcExpo8, rcControlsConfig()->deadband); - rcCommand[PITCH] = getAxisRcCommand(rxGetChannelValue(PITCH), FLIGHT_MODE(MANUAL_MODE) ? currentControlProfile->manual.rcExpo8 : currentControlProfile->stabilized.rcExpo8, rcControlsConfig()->deadband); - rcCommand[YAW] = -getAxisRcCommand(rxGetChannelValue(YAW), FLIGHT_MODE(MANUAL_MODE) ? currentControlProfile->manual.rcYawExpo8 : currentControlProfile->stabilized.rcYawExpo8, rcControlsConfig()->yaw_deadband); + // Compute ROLL PITCH and YAW command. + // Only recompute when the RX task has delivered new data (~50 Hz). + { + static int16_t cachedCmd[3] = {0, 0, 0}; + if (isRXDataNew) { + cachedCmd[ROLL] = getAxisRcCommand(rxGetChannelValue(ROLL), + FLIGHT_MODE(MANUAL_MODE) ? currentControlProfile->manual.rcExpo8 : currentControlProfile->stabilized.rcExpo8, + rcControlsConfig()->deadband); + cachedCmd[PITCH] = getAxisRcCommand(rxGetChannelValue(PITCH), + FLIGHT_MODE(MANUAL_MODE) ? currentControlProfile->manual.rcExpo8 : currentControlProfile->stabilized.rcExpo8, + rcControlsConfig()->deadband); + cachedCmd[YAW] = -getAxisRcCommand(rxGetChannelValue(YAW), + FLIGHT_MODE(MANUAL_MODE) ? currentControlProfile->manual.rcYawExpo8 : currentControlProfile->stabilized.rcYawExpo8, + rcControlsConfig()->yaw_deadband); + } + rcCommand[ROLL] = cachedCmd[ROLL]; + rcCommand[PITCH] = cachedCmd[PITCH]; + rcCommand[YAW] = cachedCmd[YAW]; + } // Apply manual control rates if (FLIGHT_MODE(MANUAL_MODE)) { @@ -418,8 +433,10 @@ static void processPilotAndFailSafeActions(float dT) //Compute THROTTLE command rcCommand[THROTTLE] = throttleStickMixedValue(); - // Signal updated rcCommand values to Failsafe system - failsafeUpdateRcCommandValues(); + // Signal updated rcCommand values to Failsafe system when new RC data arrived + if (isRXDataNew) { + failsafeUpdateRcCommandValues(); + } if (FLIGHT_MODE(HEADFREE_MODE)) { const float radDiff = degreesToRadians(DECIDEGREES_TO_DEGREES(attitude.values.yaw) - headFreeModeHold); diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index a8ca6c0c199..ca38f8d757b 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -25,7 +25,9 @@ #include "blackbox/blackbox_io.h" #include "build/assert.h" +#if !defined(SITL_BUILD) && !defined(RP2350) #include "build/atomic.h" +#endif #include "build/build_config.h" #include "build/debug.h" @@ -209,7 +211,7 @@ void init(void) // Initialize system and CPU clocks to their initial values systemInit(); -#if !defined(SITL_BUILD) +#if !defined(SITL_BUILD) && !defined(RP2350) __enable_irq(); #endif @@ -257,7 +259,7 @@ void init(void) latchActiveFeatures(); ledInit(false); -#if !defined(SITL_BUILD) +#if !defined(SITL_BUILD) && !defined(RP2350) EXTIInit(); #endif @@ -320,15 +322,13 @@ void init(void) featureClear(FEATURE_AIRMODE); } #if !defined(SITL_BUILD) - // Initialize motor and servo outpus + // Initialize motor and servo outputs if (pwmMotorAndServoInit()) { DISABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR); } else { ENABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR); } -#else - DISABLE_ARMING_FLAG(ARMING_DISABLED_PWM_OUTPUT_ERROR); #endif systemState |= SYSTEM_STATE_MOTORS_READY; @@ -742,7 +742,7 @@ void init(void) powerLimiterInit(); #endif -#if !defined(SITL_BUILD) +#ifndef SITL_BUILD // Considering that the persistent reset reason is only used during init persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE); #endif diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 4ca125d5c6a..b4e77c544ab 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -350,9 +350,8 @@ void fcTasksInit(void) schedulerInit(); rescheduleTask(TASK_PID, getLooptime()); - setTaskEnabled(TASK_PID, true); - rescheduleTask(TASK_GYRO, getGyroLooptime()); + setTaskEnabled(TASK_PID, true); setTaskEnabled(TASK_GYRO, true); setTaskEnabled(TASK_AUX, true); diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index ce9bbab4b23..5ee90315876 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -131,7 +131,7 @@ bool throttleStickIsLow(void) return calculateThrottleStatus(feature(FEATURE_REVERSIBLE_MOTORS) ? THROTTLE_STATUS_TYPE_COMMAND : THROTTLE_STATUS_TYPE_RC) == THROTTLE_LOW; } -int16_t throttleStickMixedValue(void) +int16_t RP2350_FAST_CODE throttleStickMixedValue(void) { int16_t throttleValue; uint16_t lowLimit = feature(FEATURE_REVERSIBLE_MOTORS) ? PWM_RANGE_MIN : rxConfig()->mincheck; diff --git a/src/main/fc/rc_curves.c b/src/main/fc/rc_curves.c index 52b9a685b57..ff057c96567 100644 --- a/src/main/fc/rc_curves.c +++ b/src/main/fc/rc_curves.c @@ -59,7 +59,7 @@ int16_t rcLookup(int32_t stickDeflection, uint8_t expo) return lrintf((2500.0f + (float)expo * (tmpf * tmpf - 25.0f)) * tmpf / 25.0f); } -uint16_t rcLookupThrottle(uint16_t absoluteDeflection) +uint16_t RP2350_FAST_CODE rcLookupThrottle(uint16_t absoluteDeflection) { if (absoluteDeflection > 999) return getMaxThrottle(); diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index b012c040d27..b50f812c016 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -113,8 +113,6 @@ STATIC_FASTRAM pt1Filter_t HeadVecEFFilterY; STATIC_FASTRAM pt1Filter_t HeadVecEFFilterZ; FASTRAM fpVector3_t HeadVecEFFiltered = {.v = {0.0f, 0.0f, 0.0f}}; -STATIC_FASTRAM float GPS3DspeedFiltered=0.0f; -STATIC_FASTRAM pt1Filter_t GPS3DspeedFilter; FASTRAM bool gpsHeadingInitialized; @@ -138,7 +136,7 @@ PG_RESET_TEMPLATE(imuConfig_t, imuConfig, .gps_yaw_weight = SETTING_AHRS_GPS_YAW_WEIGHT_DEFAULT ); -STATIC_UNIT_TESTED void imuComputeRotationMatrix(void) +STATIC_UNIT_TESTED RP2350_FAST_CODE void imuComputeRotationMatrix(void) { float q1q1 = orientation.q1 * orientation.q1; float q2q2 = orientation.q2 * orientation.q2; @@ -171,6 +169,12 @@ void imuConfigure(void) imuRuntimeConfig.dcm_kp_mag = imuConfig()->dcm_kp_mag / 10000.0f; imuRuntimeConfig.dcm_ki_mag = imuConfig()->dcm_ki_mag / 10000.0f; imuRuntimeConfig.small_angle = imuConfig()->small_angle; + /* Precompute the Mahony anti-windup clamp. The PID loop reads this value + * 1000× per second; the kP gains only change when the user saves settings, + * so computing it here (called once per save) avoids one add, one multiply, + * and one divide on every PID cycle. */ + imuRuntimeConfig.dcm_i_limit = DEGREES_TO_RADIANS(2.0f) + * (imuRuntimeConfig.dcm_kp_acc + imuRuntimeConfig.dcm_kp_mag) * 0.5f; } void imuInit(void) @@ -210,8 +214,6 @@ void imuInit(void) pt1FilterReset(&HeadVecEFFilterX, 0); pt1FilterReset(&HeadVecEFFilterY, 0); pt1FilterReset(&HeadVecEFFilterZ, 0); - // Initialize 3d speed filter - pt1FilterReset(&GPS3DspeedFilter, 0); } void imuSetMagneticDeclination(float declinationDeg) @@ -222,7 +224,7 @@ void imuSetMagneticDeclination(float declinationDeg) vCorrectedMagNorth.z = 0; } -void imuTransformVectorBodyToEarth(fpVector3_t * v) +RP2350_FAST_CODE void imuTransformVectorBodyToEarth(fpVector3_t * v) { // From body frame to earth frame quaternionRotateVectorInv(v, v, &orientation); @@ -365,10 +367,23 @@ static float imuCalculateMcCogAccWeight(void) return wCoGAcc; } -static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVector3_t * accBF, const fpVector3_t * magBF, const fpVector3_t * vCOG, const fpVector3_t * vCOGAcc, float accWScaler, float magWScaler) +static RP2350_FAST_CODE void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVector3_t * accBF, const fpVector3_t * magBF, const fpVector3_t * vCOG, const fpVector3_t * vCOGAcc, float accWScaler, float magWScaler) { STATIC_FASTRAM fpVector3_t vGyroDriftEstimate = { 0 }; - fpQuaternion_t prevOrientation = orientation; + + /* Opt 5: snapshot prevOrientation every 10 PID cycles instead of every cycle. + * The snapshot is only used by the fault-recovery path in + * imuCheckAndResetOrientationQuaternion(), which should never fire in normal + * flight. Copying 4 floats 1000×/s just to support a near-zero-probability + * reset path is wasteful; 10 ms staleness gives a fresh recovery point + * while reducing copy overhead by 10×. */ + static uint8_t prevOrientationSnapshotCount = 0; + static fpQuaternion_t prevOrientation = { .q0 = 1.0f }; // identity quaternion safe default + if (++prevOrientationSnapshotCount >= 10) { + prevOrientationSnapshotCount = 0; + prevOrientation = orientation; + } + fpVector3_t vRotation = *gyroBF; /* Calculate general spin rate (rad/s) */ @@ -501,11 +516,17 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe /* Step 2: Roll and pitch correction - use measured acceleration vector */ if (accBF) { - static const fpVector3_t vGravity = { .v = { 0.0f, 0.0f, 1.0f } }; fpVector3_t vEstGravity, vAcc, vErr; - // Calculate estimated gravity vector in body frame - quaternionRotateVector(&vEstGravity, &vGravity, &orientation); // EF -> BF + /* Opt 1: imuComputeRotationMatrix() is called at the END of every + * imuMahonyAHRSupdate() and keeps rMat in sync with orientation. + * Rotating the constant unit-gravity vector {0,0,1} from EF to BF by + * the current orientation quaternion yields exactly the third row of rMat + * (rMat[2][0..2]). Reading those three floats replaces a quaternionRotateVector() + * call that costs 2× quaternionMultiply = ~32 multiplies + 24 adds. */ + vEstGravity.x = rMat[2][0]; + vEstGravity.y = rMat[2][1]; + vEstGravity.z = rMat[2][2]; // Error is sum of cross product between estimated direction and measured direction of gravity vectorNormalize(&vAcc, accBF); @@ -528,7 +549,9 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe vectorAdd(&vRotation, &vRotation, &vErr); } // Anti wind-up - float i_limit = DEGREES_TO_RADIANS(2.0f) * (imuRuntimeConfig.dcm_kp_acc + imuRuntimeConfig.dcm_kp_mag) / 2.0f; + /* Opt 4: dcm_i_limit is computed once in imuConfigure() (called on settings save), + * not recomputed each PID cycle. The kP gains do not change at runtime. */ + const float i_limit = imuRuntimeConfig.dcm_i_limit; vGyroDriftEstimate.x = constrainf(vGyroDriftEstimate.x, -i_limit, i_limit); vGyroDriftEstimate.y = constrainf(vGyroDriftEstimate.y, -i_limit, i_limit); vGyroDriftEstimate.z = constrainf(vGyroDriftEstimate.z, -i_limit, i_limit); @@ -551,7 +574,10 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe // Proper quaternion from axis/angle involves computing sin/cos, but the formula becomes numerically unstable as Theta approaches zero. // For near-zero cases we use the first 3 terms of the Taylor series expansion for sin/cos. We check if fourth term is less than machine precision - // then we can safely use the "low angle" approximated version without loss of accuracy. - if (thetaMagnitudeSq < fast_fsqrtf(24.0f * 1e-6f)) { + /* Opt 2: original condition was "thetaMagnitudeSq < sqrt(24e-6)". + * Squaring both sides (both are non-negative) gives an equivalent + * condition without a sqrt() call: thetaMagnitudeSq² < 24e-6. */ + if (thetaMagnitudeSq * thetaMagnitudeSq < 24.0e-6f) { quaternionScale(&deltaQ, &deltaQ, 1.0f - thetaMagnitudeSq / 6.0f); deltaQ.q0 = 1.0f - thetaMagnitudeSq / 2.0f; } @@ -563,7 +589,20 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe // Calculate final orientation and renormalize quaternionMultiply(&orientation, &orientation, &deltaQ); - quaternionNormalize(&orientation, &orientation); + /* Opt 3: first-order Newton renormalization avoids sqrt() and 4 divides. + * At 1 kHz the quaternion norm drifts by < 1e-6 per step, so normSq = 1 + ε + * with |ε| ≪ 1. The identity 1/sqrt(x) ≈ (3-x)/2 is accurate to O(ε²) ≈ 1e-12 + * — well within float precision. imuCheckAndResetOrientationQuaternion() below + * catches any catastrophic norm deviation that this approximation cannot correct. */ + { + const float normSq = orientation.q0 * orientation.q0 + orientation.q1 * orientation.q1 + + orientation.q2 * orientation.q2 + orientation.q3 * orientation.q3; + const float scale = (3.0f - normSq) * 0.5f; + orientation.q0 *= scale; + orientation.q1 *= scale; + orientation.q2 *= scale; + orientation.q3 *= scale; + } } // Check for invalid quaternion and reset to previous known good one @@ -573,7 +612,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe imuComputeRotationMatrix(); } -STATIC_UNIT_TESTED void imuUpdateEulerAngles(void) +STATIC_UNIT_TESTED RP2350_FAST_CODE void imuUpdateEulerAngles(void) { #ifdef USE_SIMULATOR if ((ARMING_FLAG(SIMULATOR_MODE_HITL) && !SIMULATOR_HAS_OPTION(HITL_USE_IMU)) || (ARMING_FLAG(SIMULATOR_MODE_SITL) && imuUpdated)) { @@ -667,9 +706,6 @@ static void imuCalculateFilters(float dT) HeadVecEFFiltered.y = pt1FilterApply4(&HeadVecEFFilterY, rMat[1][0], IMU_ROTATION_LPF, dT); HeadVecEFFiltered.z = pt1FilterApply4(&HeadVecEFFilterZ, rMat[2][0], IMU_ROTATION_LPF, dT); - //anti aliasing - float GPS3Dspeed = calc_length_pythagorean_3D(gpsSol.velNED[X],gpsSol.velNED[Y],gpsSol.velNED[Z]); - GPS3DspeedFiltered = pt1FilterApply4(&GPS3DspeedFilter, GPS3Dspeed, IMU_ROTATION_LPF, dT); } static void imuCalculateGPSacceleration(fpVector3_t *vEstAccelEF,fpVector3_t *vEstcentrifugalAccelBF, float *acc_ignore_slope_multipiler) @@ -705,6 +741,14 @@ static void imuCalculateTurnRateacceleration(fpVector3_t *vEstcentrifugalAccelBF float currentspeed = 0; if (isGPSTrustworthy()){ //first speed choice is gps + static bool lastGPSHeartbeat; + static pt1Filter_t GPS3DspeedFilter; + static float GPS3DspeedFiltered = 0.0f; + if (gpsSol.flags.gpsHeartbeat != lastGPSHeartbeat) { + lastGPSHeartbeat = gpsSol.flags.gpsHeartbeat; + float GPS3Dspeed = calc_length_pythagorean_3D(gpsSol.velNED[X], gpsSol.velNED[Y], gpsSol.velNED[Z]); + GPS3DspeedFiltered = pt1FilterApply4(&GPS3DspeedFilter, GPS3Dspeed, IMU_ROTATION_LPF, dT); + } currentspeed = GPS3DspeedFiltered; *acc_ignore_slope_multipiler = 4.0f; } @@ -756,7 +800,7 @@ void imuUpdateTailSitter(void) lastTailSitter = STATE(TAILSITTER); } -static void imuCalculateEstimatedAttitude(float dT) +static RP2350_FAST_CODE void imuCalculateEstimatedAttitude(float dT) { #if defined(USE_MAG) const bool canUseMAG = sensors(SENSOR_MAG) && compassIsHealthy(); diff --git a/src/main/flight/imu.h b/src/main/flight/imu.h index 6d285d0f794..14244c9cefc 100644 --- a/src/main/flight/imu.h +++ b/src/main/flight/imu.h @@ -65,6 +65,11 @@ typedef struct imuRuntimeConfig_s { float dcm_ki_acc; float dcm_kp_mag; float dcm_ki_mag; + /* Precomputed anti-windup limit for imuMahonyAHRSupdate(): equals + * DEGREES_TO_RADIANS(2) * (dcm_kp_acc + dcm_kp_mag) / 2. + * Updated once by imuConfigure() whenever settings are saved, so the + * hot PID path reads a single float instead of doing arithmetic. */ + float dcm_i_limit; uint8_t small_angle; } imuRuntimeConfig_t; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 0a2faa648ca..354ffeff371 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -117,6 +117,7 @@ typedef struct { smithPredictor_t smithPredictor; fwPidAttenuation_t attenuation; + uint16_t pidSumLimit; } pidState_t; STATIC_FASTRAM bool pidFiltersConfigured = false; @@ -413,7 +414,7 @@ float getAxisIterm(uint8_t axis) return pidState[axis].errorGyroIf; } -static float pidRcCommandToAngle(int16_t stick, int16_t maxInclination) +static float FAST_CODE pidRcCommandToAngle(int16_t stick, int16_t maxInclination) { stick = constrain(stick, -500, 500); return scaleRangef((float) stick, -500.0f, 500.0f, (float) -maxInclination, (float) maxInclination); @@ -436,7 +437,7 @@ float pidRateToRcCommand(float rateDPS, uint8_t rate) return scaleRangef(rateDPS, -maxRateDPS, maxRateDPS, -500.0f, 500.0f); } -float pidRcCommandToRate(int16_t stick, uint8_t rate) +float FAST_CODE pidRcCommandToRate(int16_t stick, uint8_t rate) { const float maxRateDPS = rate * 10.0f; return scaleRangef((float) stick, -500.0f, 500.0f, -maxRateDPS, maxRateDPS); @@ -725,7 +726,7 @@ static void pidLevel(const float angleTarget, pidState_t *pidState, flight_dynam } /* Apply angular acceleration limit to rate target to limit extreme stick inputs to respect physical capabilities of the machine */ -static void pidApplySetpointRateLimiting(pidState_t *pidState, flight_dynamics_index_t axis, float dT) +static void FAST_CODE pidApplySetpointRateLimiting(pidState_t *pidState, flight_dynamics_index_t axis, float dT) { const uint32_t axisAccelLimit = (axis == FD_YAW) ? pidProfile()->axisAccelerationLimitYaw : pidProfile()->axisAccelerationLimitRollPitch; @@ -734,7 +735,7 @@ static void pidApplySetpointRateLimiting(pidState_t *pidState, flight_dynamics_i } } -static float pTermProcess(pidState_t *pidState, float rateError, float dT) { +static float FAST_CODE pTermProcess(pidState_t *pidState, float rateError, float dT) { float newPTerm = rateError * pidState->kP; return pidState->ptermFilterApplyFn(&pidState->ptermLpfState, newPTerm, yawLpfHz, dT); @@ -770,7 +771,7 @@ static float applyDBoost(pidState_t *pidState, float dT) { } #endif -static float dTermProcess(pidState_t *pidState, float currentRateTarget, float dT, float dT_inv) { +static float FAST_CODE dTermProcess(pidState_t *pidState, float currentRateTarget, float dT, float dT_inv) { // Calculate new D-term float newDTerm = 0; if (pidState->kD == 0) { @@ -787,7 +788,7 @@ static float dTermProcess(pidState_t *pidState, float currentRateTarget, float d return(newDTerm); } -static void applyItermLimiting(pidState_t *pidState) { +static void FAST_CODE applyItermLimiting(pidState_t *pidState) { if (pidState->itermLimitActive) { pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit); } else @@ -861,7 +862,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, float applyItermLimiting(pidState); - const uint16_t limit = getPidSumLimit(pidState->axis); + const uint16_t limit = pidState->pidSumLimit; if (pidProfile()->pidItermLimitPercent != 0){ float itermLimit = limit * pidProfile()->pidItermLimitPercent * 0.01f; @@ -927,7 +928,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid */ const float newCDTerm = rateTargetDeltaFiltered * pidState->kCD; - const uint16_t limit = getPidSumLimit(pidState->axis); + const uint16_t limit = pidState->pidSumLimit; // TODO: Get feedback from mixer on available correction range for each axis const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm; @@ -1136,7 +1137,7 @@ static void pidApplyFpvCameraAngleMix(pidState_t *pidState, uint8_t fpvCameraAng pidState[YAW].rateTarget = constrainf(yawRate * cosCameraAngle + rollRate * sinCameraAngle, -GYRO_SATURATION_LIMIT, GYRO_SATURATION_LIMIT); } -void checkItermLimitingActive(pidState_t *pidState) +void FAST_CODE checkItermLimitingActive(pidState_t *pidState) { bool shouldActivate = false; @@ -1147,7 +1148,7 @@ void checkItermLimitingActive(pidState_t *pidState) pidState->itermLimitActive = STATE(ANTI_WINDUP) || shouldActivate; } -void checkItermFreezingActive(pidState_t *pidState, flight_dynamics_index_t axis) +void FAST_CODE checkItermFreezingActive(pidState_t *pidState, flight_dynamics_index_t axis) { if (usedPidControllerType == PID_TYPE_PIFF && pidProfile()->fixedWingYawItermBankFreeze != 0 && axis == FD_YAW) { // Do not allow yaw I-term to grow when bank angle is too large @@ -1376,6 +1377,7 @@ void pidInit(void) #endif pidState[axis].axis = axis; + pidState[axis].pidSumLimit = getPidSumLimit(axis); if (axis == FD_YAW) { if (yawLpfHz) { pidState[axis].ptermFilterApplyFn = (filterApply4FnPtr) pt1FilterApply4; diff --git a/src/main/flight/smith_predictor.c b/src/main/flight/smith_predictor.c index 6a363c4f231..78151215ff5 100644 --- a/src/main/flight/smith_predictor.c +++ b/src/main/flight/smith_predictor.c @@ -34,7 +34,7 @@ #include "flight/smith_predictor.h" #include "build/debug.h" -float applySmithPredictor(uint8_t axis, smithPredictor_t *predictor, float sample) { +float FAST_CODE applySmithPredictor(uint8_t axis, smithPredictor_t *predictor, float sample) { UNUSED(axis); if (predictor->enabled) { predictor->data[predictor->idx] = sample; diff --git a/src/main/flight/wind_estimator.c b/src/main/flight/wind_estimator.c index 7567d0ad257..1fd8e72da56 100644 --- a/src/main/flight/wind_estimator.c +++ b/src/main/flight/wind_estimator.c @@ -174,11 +174,12 @@ void updateWindEstimator(timeUs_t currentTimeUs) wind[Y] = (groundVelocitySum[Y] - V * (sintheta * fuselageDirectionSum[X] + costheta * fuselageDirectionSum[Y])) * 0.5f;// equation 11 wind[Z] = (groundVelocitySum[Z] - V * fuselageDirectionSum[Z]) * 0.5f;// equation 12 - float prevWindLength = calc_length_pythagorean_3D(estimatedWind[X], estimatedWind[Y], estimatedWind[Z]); - float windLength = calc_length_pythagorean_3D(wind[X], wind[Y], wind[Z]); + float prevWindSq = sq(estimatedWind[X]) + sq(estimatedWind[Y]) + sq(estimatedWind[Z]); + float windSq = sq(wind[X]) + sq(wind[Y]) + sq(wind[Z]); //is this really needed? The reason it is here might be above equation was wrong in early implementations - if (windLength < prevWindLength + 4000) { + // Equivalent to: sqrt(windSq) < sqrt(prevWindSq) + 4000 + if (windSq < sq(fast_fsqrtf(prevWindSq) + 4000.0f)) { // TODO: Better filtering estimatedWind[X] = estimatedWind[X] * 0.98f + wind[X] * 0.02f; estimatedWind[Y] = estimatedWind[Y] * 0.98f + wind[Y] * 0.02f; diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 35245d9f7f0..62ca92b28a6 100644 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -351,7 +351,7 @@ static bool gravityCalibrationComplete(void) #define ACC_VIB_FACTOR_S 1.0f #define ACC_VIB_FACTOR_E 3.0f -static void updateIMUEstimationWeight(const float dt) +static RP2350_FAST_CODE void updateIMUEstimationWeight(const float dt) { static float acc_clip_factor = 1.0f; // If accelerometer measurement is clipped - drop the acc weight to 0.3 @@ -370,7 +370,7 @@ static void updateIMUEstimationWeight(const float dt) DEBUG_SET(DEBUG_VIBE, 4, posEstimator.imu.accWeightFactor * 1000); } -static void updateIMUTopic(timeUs_t currentTimeUs) +static RP2350_FAST_CODE void updateIMUTopic(timeUs_t currentTimeUs) { const float dt = US2S(currentTimeUs - posEstimator.imu.lastUpdateTime); posEstimator.imu.lastUpdateTime = currentTimeUs; @@ -718,7 +718,7 @@ static void estimationCalculateGroundCourse(timeUs_t currentTimeUs) * Calculate next estimate using IMU and apply corrections from reference sensors (GPS, BARO etc) * Function is called at main loop rate */ -static void updateEstimatedTopic(timeUs_t currentTimeUs) +static RP2350_FAST_CODE void updateEstimatedTopic(timeUs_t currentTimeUs) { estimationContext_t ctx; @@ -911,7 +911,7 @@ void initializePositionEstimator(void) * Update estimator * Update rate: loop rate (>100Hz) */ -void updatePositionEstimator(void) +RP2350_FAST_CODE void updatePositionEstimator(void) { static bool isInitialized = false; diff --git a/src/main/platform.h b/src/main/platform.h index 8c4429746d1..ba8689d1d8a 100644 --- a/src/main/platform.h +++ b/src/main/platform.h @@ -78,6 +78,9 @@ typedef enum #define U_ID_1 (*(uint32_t*)0x1fff7a14) #define U_ID_2 (*(uint32_t*)0x1fff7a18) +#elif defined(RP2350) +#include "rp2350.h" + #endif #include "target/common.h" diff --git a/src/main/rp2350.h b/src/main/rp2350.h new file mode 100644 index 00000000000..fa9b2631071 --- /dev/null +++ b/src/main/rp2350.h @@ -0,0 +1,111 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +/* + * rp2350.h — chip-level type stubs for the RP2350 port. + * + * Included by platform.h in place of the vendor HAL headers that INAV's + * generic driver layer expects on STM32 (stm32f7xx.h, stm32h7xx.h, …). + * Only the fields and constants actually referenced by shared INAV code + * are defined; everything else is a void* placeholder. + */ + +#pragma once + +#include +#include + +/* ── Chip unique ID ────────────────────────────────────────────────────────── */ + +#define U_ID_0 0 +#define U_ID_1 1 +#define U_ID_2 2 + +extern uint32_t SystemCoreClock; + +/* ── Timer ─────────────────────────────────────────────────────────────────── */ + +typedef struct { void* dummy; } TIM_TypeDef; +typedef struct { void* dummy; } TIM_OCInitTypeDef; + +/* ── DMA ───────────────────────────────────────────────────────────────────── */ + +typedef struct { void* dummy; } DMA_TypeDef; +typedef struct { void* dummy; } DMA_Channel_TypeDef; + +/* ── SPI ───────────────────────────────────────────────────────────────────── */ + +typedef struct { void* dummy; } SPI_TypeDef; + +/* RP2350-only identity tokens — NOT hardware register addresses. + * Used only by bus_spi_rp2350.c to select spi0/spi1 by INAV device index. + * Do not use in shared INAV driver code. */ +#define SPI1 ((SPI_TypeDef *)0x0001) +#define SPI2 ((SPI_TypeDef *)0x0002) + +/* ── I2C ───────────────────────────────────────────────────────────────────── */ + +typedef struct { void* dummy; } I2C_TypeDef; + +/* ── GPIO ──────────────────────────────────────────────────────────────────── */ + +typedef struct +{ + uint32_t IDR; + uint32_t ODR; + uint32_t BSRR; + uint32_t BRR; +} GPIO_TypeDef; + +#define GPIOA_BASE ((intptr_t)0x0001) + +/* ── USART / UART ──────────────────────────────────────────────────────────── */ + +typedef struct { uint32_t dummy; } USART_TypeDef; + +#define USART1 ((USART_TypeDef *)0x0001) +#define USART2 ((USART_TypeDef *)0x0002) +#define USART3 ((USART_TypeDef *)0x0003) +#define USART4 ((USART_TypeDef *)0x0004) +#define USART5 ((USART_TypeDef *)0x0005) +#define USART6 ((USART_TypeDef *)0x0006) +#define USART7 ((USART_TypeDef *)0x0007) +#define USART8 ((USART_TypeDef *)0x0008) + +/* Aliases for code that uses UARTx names rather than USARTx names. */ +#define UART4 ((USART_TypeDef *)0x0004) +#define UART5 ((USART_TypeDef *)0x0005) +#define UART7 ((USART_TypeDef *)0x0007) +#define UART8 ((USART_TypeDef *)0x0008) + +/* ── Misc HAL enums ────────────────────────────────────────────────────────── */ + +typedef enum { RESET = 0, SET = !RESET } FlagStatus, ITStatus; +typedef enum { DISABLE = 0, ENABLE = !DISABLE } FunctionalState; +typedef enum { TEST_IRQ = 0 } IRQn_Type; +typedef enum { + EXTI_Trigger_Rising = 0x08, + EXTI_Trigger_Falling = 0x0C, + EXTI_Trigger_Rising_Falling = 0x10 +} EXTITrigger_TypeDef; diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 16d10624c69..e93575249a8 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -527,11 +527,11 @@ const acc_extremes_t* accGetMeasuredExtremes(void) float accGetMeasuredMaxG(void) { - return acc.maxG; + return fast_fsqrtf(acc.maxGSq); } void resetGForceStats(void) { - acc.maxG = 0.0f; + acc.maxGSq = 0.0f; for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { acc.extremes[axis].min = 100; @@ -610,8 +610,8 @@ void updateAccExtremes(void) if (acc.accADCf[axis] > acc.extremes[axis].max) acc.extremes[axis].max = acc.accADCf[axis]; } - float gforce = calc_length_pythagorean_3D(acc.accADCf[X], acc.accADCf[Y], acc.accADCf[Z]); - if (gforce > acc.maxG) acc.maxG = gforce; + float gforceSq = sq(acc.accADCf[X]) + sq(acc.accADCf[Y]) + sq(acc.accADCf[Z]); + if (gforceSq > acc.maxGSq) acc.maxGSq = gforceSq; } void accGetVibrationLevels(fpVector3_t *accVibeLevels) diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index 2e2bfa461e0..8d479c70c26 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -62,7 +62,7 @@ typedef struct acc_s { uint32_t accClipCount; bool isClipped; acc_extremes_t extremes[XYZ_AXIS_COUNT]; - float maxG; + float maxGSq; } acc_t; extern acc_t acc; diff --git a/src/main/startup/boot2_rp2350.S b/src/main/startup/boot2_rp2350.S new file mode 100644 index 00000000000..5fca131490b --- /dev/null +++ b/src/main/startup/boot2_rp2350.S @@ -0,0 +1,29 @@ +/* + * Boot2 stage 2 bootloader stub for RP2350 + * + * Minimal placeholder for M1 (build system milestone). + * For real hardware, replace with a proper boot2 from the Pico SDK. + * + * Must be exactly 256 bytes in the .boot2 section. + */ + + .syntax unified + .cpu cortex-m33 + .thumb + + .section .boot2, "ax" + + .global _boot2_entry + .type _boot2_entry, %function +_boot2_entry: + /* Load address of vector table (0x10000100 = flash base + 256) */ + movw r0, #0x0100 + movt r0, #0x1000 + /* Load reset vector from vector table */ + ldr r1, [r0, #4] + bx r1 + .ltorg + .size _boot2_entry, . - _boot2_entry + + /* Pad remainder with zeros to exactly 256 bytes */ + .balign 256, 0 diff --git a/src/main/startup/startup_rp2350.s b/src/main/startup/startup_rp2350.s new file mode 100644 index 00000000000..afdf513d6fd --- /dev/null +++ b/src/main/startup/startup_rp2350.s @@ -0,0 +1,288 @@ +/** + * Minimal startup for RP2350 (Cortex-M33) + * + * Performs: + * - Set initial SP + * - Copy .data from flash to RAM + * - Zero .bss + * - Call SystemInit (if present) + * - Call main + */ + + .syntax unified + .cpu cortex-m33 + .fpu fpv5-sp-d16 + .thumb + +.global g_pfnVectors +.global Default_Handler +.global _entry_point + +/* Linker script symbols */ +.word _sidata +.word _sdata +.word _edata +.word _sbss +.word _ebss + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + /* Set stack pointer */ + ldr r0, =_estack + msr msp, r0 + + /* Copy .data section from flash to RAM */ + ldr r0, =_sdata + ldr r1, =_edata + ldr r2, =_sidata + movs r3, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r4, [r2, r3] + str r4, [r0, r3] + adds r3, r3, #4 + +LoopCopyDataInit: + adds r4, r0, r3 + cmp r4, r1 + bcc CopyDataInit + + /* Zero .bss section */ + ldr r2, =_sbss + ldr r4, =_ebss + movs r3, #0 + b LoopFillZerobss + +FillZerobss: + str r3, [r2] + adds r2, r2, #4 + +LoopFillZerobss: + cmp r2, r4 + bcc FillZerobss + + /* Call SystemInit if it exists */ + bl SystemInit + + /* Call main */ + bl main + + /* If main returns, loop forever */ + b . + + .size Reset_Handler, . - Reset_Handler + +/** + * Default handler for unhandled interrupts + */ + .section .text.Default_Handler, "ax", %progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, . - Default_Handler + +/** + * Minimal vector table (placed in .isr_vector section) + */ + .section .isr_vector, "a", %progbits + .type g_pfnVectors, %object + .size g_pfnVectors, . - g_pfnVectors + +g_pfnVectors: + .word _estack /* Top of Stack */ + .word Reset_Handler /* Reset Handler */ + .word NMI_Handler /* NMI Handler */ + .word HardFault_Handler /* Hard Fault Handler */ + .word MemManage_Handler /* MPU Fault Handler */ + .word BusFault_Handler /* Bus Fault Handler */ + .word UsageFault_Handler /* Usage Fault Handler */ + .word SecureFault_Handler /* Secure Fault Handler (ARMv8-M) */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word SVC_Handler /* SVCall Handler */ + .word DebugMon_Handler /* Debug Monitor Handler */ + .word 0 /* Reserved */ + .word PendSV_Handler /* PendSV Handler */ + .word SysTick_Handler /* SysTick Handler */ + + /* RP2350 peripheral interrupts - 52 IRQs */ + .word TIMER0_IRQ_0_Handler + .word TIMER0_IRQ_1_Handler + .word TIMER0_IRQ_2_Handler + .word TIMER0_IRQ_3_Handler + .word TIMER1_IRQ_0_Handler + .word TIMER1_IRQ_1_Handler + .word TIMER1_IRQ_2_Handler + .word TIMER1_IRQ_3_Handler + .word PWM_IRQ_WRAP_0_Handler + .word PWM_IRQ_WRAP_1_Handler + .word DMA_IRQ_0_Handler + .word DMA_IRQ_1_Handler + .word DMA_IRQ_2_Handler + .word DMA_IRQ_3_Handler + .word USBCTRL_IRQ_Handler + .word PIO0_IRQ_0_Handler + .word PIO0_IRQ_1_Handler + .word PIO1_IRQ_0_Handler + .word PIO1_IRQ_1_Handler + .word PIO2_IRQ_0_Handler + .word PIO2_IRQ_1_Handler + .word IO_IRQ_BANK0_Handler + .word IO_IRQ_QSPI_Handler + .word SIO_IRQ_FIFO_Handler + .word SPI0_IRQ_Handler + .word SPI1_IRQ_Handler + .word UART0_IRQ_Handler + .word UART1_IRQ_Handler + .word ADC_IRQ_FIFO_Handler + .word I2C0_IRQ_Handler + .word I2C1_IRQ_Handler + .word OTP_IRQ_Handler + .word TRNG_IRQ_Handler + .word 0 /* Reserved (PROC0_IRQ_CTI) */ + .word 0 /* Reserved (PROC1_IRQ_CTI) */ + .word PLL_SYS_IRQ_Handler + .word PLL_USB_IRQ_Handler + .word POWMAN_IRQ_POW_Handler + .word POWMAN_IRQ_TIMER_Handler + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word SWI_IRQ_0_Handler + .word SWI_IRQ_1_Handler + .word SWI_IRQ_2_Handler + .word SWI_IRQ_3_Handler + .word SWI_IRQ_4_Handler + .word SWI_IRQ_5_Handler + +/** + * Weak aliases for interrupt handlers - default to Default_Handler + */ + .weak NMI_Handler + .thumb_set NMI_Handler, Default_Handler + .weak HardFault_Handler + .thumb_set HardFault_Handler, Default_Handler + .weak MemManage_Handler + .thumb_set MemManage_Handler, Default_Handler + .weak BusFault_Handler + .thumb_set BusFault_Handler, Default_Handler + .weak UsageFault_Handler + .thumb_set UsageFault_Handler, Default_Handler + .weak SecureFault_Handler + .thumb_set SecureFault_Handler, Default_Handler + .weak SVC_Handler + .thumb_set SVC_Handler, Default_Handler + .weak DebugMon_Handler + .thumb_set DebugMon_Handler, Default_Handler + .weak PendSV_Handler + .thumb_set PendSV_Handler, Default_Handler + .weak SysTick_Handler + .thumb_set SysTick_Handler, Default_Handler + + .weak TIMER0_IRQ_0_Handler + .thumb_set TIMER0_IRQ_0_Handler, Default_Handler + .weak TIMER0_IRQ_1_Handler + .thumb_set TIMER0_IRQ_1_Handler, Default_Handler + .weak TIMER0_IRQ_2_Handler + .thumb_set TIMER0_IRQ_2_Handler, Default_Handler + .weak TIMER0_IRQ_3_Handler + .thumb_set TIMER0_IRQ_3_Handler, Default_Handler + .weak TIMER1_IRQ_0_Handler + .thumb_set TIMER1_IRQ_0_Handler, Default_Handler + .weak TIMER1_IRQ_1_Handler + .thumb_set TIMER1_IRQ_1_Handler, Default_Handler + .weak TIMER1_IRQ_2_Handler + .thumb_set TIMER1_IRQ_2_Handler, Default_Handler + .weak TIMER1_IRQ_3_Handler + .thumb_set TIMER1_IRQ_3_Handler, Default_Handler + .weak PWM_IRQ_WRAP_0_Handler + .thumb_set PWM_IRQ_WRAP_0_Handler, Default_Handler + .weak PWM_IRQ_WRAP_1_Handler + .thumb_set PWM_IRQ_WRAP_1_Handler, Default_Handler + .weak DMA_IRQ_0_Handler + .thumb_set DMA_IRQ_0_Handler, Default_Handler + .weak DMA_IRQ_1_Handler + .thumb_set DMA_IRQ_1_Handler, Default_Handler + .weak DMA_IRQ_2_Handler + .thumb_set DMA_IRQ_2_Handler, Default_Handler + .weak DMA_IRQ_3_Handler + .thumb_set DMA_IRQ_3_Handler, Default_Handler + .weak USBCTRL_IRQ_Handler + .thumb_set USBCTRL_IRQ_Handler, Default_Handler + .weak PIO0_IRQ_0_Handler + .thumb_set PIO0_IRQ_0_Handler, Default_Handler + .weak PIO0_IRQ_1_Handler + .thumb_set PIO0_IRQ_1_Handler, Default_Handler + .weak PIO1_IRQ_0_Handler + .thumb_set PIO1_IRQ_0_Handler, Default_Handler + .weak PIO1_IRQ_1_Handler + .thumb_set PIO1_IRQ_1_Handler, Default_Handler + .weak PIO2_IRQ_0_Handler + .thumb_set PIO2_IRQ_0_Handler, Default_Handler + .weak PIO2_IRQ_1_Handler + .thumb_set PIO2_IRQ_1_Handler, Default_Handler + .weak IO_IRQ_BANK0_Handler + .thumb_set IO_IRQ_BANK0_Handler, Default_Handler + .weak IO_IRQ_QSPI_Handler + .thumb_set IO_IRQ_QSPI_Handler, Default_Handler + .weak SIO_IRQ_FIFO_Handler + .thumb_set SIO_IRQ_FIFO_Handler, Default_Handler + .weak SPI0_IRQ_Handler + .thumb_set SPI0_IRQ_Handler, Default_Handler + .weak SPI1_IRQ_Handler + .thumb_set SPI1_IRQ_Handler, Default_Handler + .weak UART0_IRQ_Handler + .thumb_set UART0_IRQ_Handler, Default_Handler + .weak UART1_IRQ_Handler + .thumb_set UART1_IRQ_Handler, Default_Handler + .weak ADC_IRQ_FIFO_Handler + .thumb_set ADC_IRQ_FIFO_Handler, Default_Handler + .weak I2C0_IRQ_Handler + .thumb_set I2C0_IRQ_Handler, Default_Handler + .weak I2C1_IRQ_Handler + .thumb_set I2C1_IRQ_Handler, Default_Handler + .weak OTP_IRQ_Handler + .thumb_set OTP_IRQ_Handler, Default_Handler + .weak TRNG_IRQ_Handler + .thumb_set TRNG_IRQ_Handler, Default_Handler + .weak PLL_SYS_IRQ_Handler + .thumb_set PLL_SYS_IRQ_Handler, Default_Handler + .weak PLL_USB_IRQ_Handler + .thumb_set PLL_USB_IRQ_Handler, Default_Handler + .weak POWMAN_IRQ_POW_Handler + .thumb_set POWMAN_IRQ_POW_Handler, Default_Handler + .weak POWMAN_IRQ_TIMER_Handler + .thumb_set POWMAN_IRQ_TIMER_Handler, Default_Handler + .weak SWI_IRQ_0_Handler + .thumb_set SWI_IRQ_0_Handler, Default_Handler + .weak SWI_IRQ_1_Handler + .thumb_set SWI_IRQ_1_Handler, Default_Handler + .weak SWI_IRQ_2_Handler + .thumb_set SWI_IRQ_2_Handler, Default_Handler + .weak SWI_IRQ_3_Handler + .thumb_set SWI_IRQ_3_Handler, Default_Handler + .weak SWI_IRQ_4_Handler + .thumb_set SWI_IRQ_4_Handler, Default_Handler + .weak SWI_IRQ_5_Handler + .thumb_set SWI_IRQ_5_Handler, Default_Handler + +/** + * Entry point - jump over boot2 to Reset_Handler + * The _entry_point is what the linker ENTRY() references. + * On RP2350, the boot ROM loads boot2 from the first 256 bytes of flash, + * executes it, then jumps to the vector table that follows. + */ + .section .text._entry_point + .type _entry_point, %function +_entry_point: + b Reset_Handler + .size _entry_point, . - _entry_point diff --git a/src/main/target/RP2350_PICO/CMakeLists.txt b/src/main/target/RP2350_PICO/CMakeLists.txt new file mode 100644 index 00000000000..4d26fbd0534 --- /dev/null +++ b/src/main/target/RP2350_PICO/CMakeLists.txt @@ -0,0 +1 @@ +target_rp2350(RP2350_PICO SKIP_RELEASES) diff --git a/src/main/target/RP2350_PICO/TODO.md b/src/main/target/RP2350_PICO/TODO.md new file mode 100644 index 00000000000..7cfabf7874d --- /dev/null +++ b/src/main/target/RP2350_PICO/TODO.md @@ -0,0 +1,356 @@ +# RP2350_PICO Port — TODO / Pending Work + +## Status +- M4 COMPLETE: INAV Configurator connects successfully and shows board name, firmware + version, sensor status. +- USB VCP (TinyUSB CDC) working; MSP protocol functional over USB. + +--- + +## Task Timings + +### Baseline (before optimizations, with dynamic notch enabled, 500 Hz) + +``` +Task list rate/hz max/us avg/us maxload avgload total/ms + 0 - SYSTEM 9 378 1 0.8% 0.5% 204 + 1 - PID 405 2337 1464 95.1% 59.7% 18521 + 2 - GYRO 408 459 37 19.2% 2.0% 444 + 3 - RX 48 884 414 4.7% 2.4% 670 + 4 - SERIAL 94 1285653 83 12085.6% 1.2% 3318 + 6 - TEMPERATURE 99 390 35 4.3% 0.8% 81 +Total (excluding SERIAL) 135.2% 69.7% +``` + +### After optimizations (FAST_CODE callees, pidSumLimit precompute, isRXDataNew cache, 1 kHz) + +``` +Task list rate/hz max/us avg/us maxload avgload total/ms + 1 - PID 993 1398 690 139.3% 69.0% 70605 + 2 - GYRO 993 343 15 34.5% 1.9% 1394 + 3 - RX 49 747 389 4.1% 2.4% 2588 +Total (excluding SERIAL) 190.8% 78.6% +``` + +Root cause of remaining PID cost: dominant functions still run from QSPI flash (XIP cache). + +### PID loop profiling breakdown (early-return, 1 kHz, no GPS) + +| Profiling point | PID avg | Delta | Code section | +|---|---|---|---| +| after `gyroFilter()` | 9 µs | — | Gyro filter chain | +| after `imuUpdateAttitude()` | 317 µs | **+308 µs** | **IMU (Mahony AHRS + attitude) ← dominant** | +| after `processPilotAndFailSafe()` | 404 µs | +87 µs | RC processing + failsafe | +| after `updatePositionEstimator()` | 519 µs | +115 µs | Navigation / position estimator | +| after `pidController()` | 653 µs | +134 µs | PID computation | +| after `mixTable()` | 665 µs | +12 µs | Mixer + output | + +IMU accounts for 46% of PID loop time (308/665 µs). This is the primary target for +TODO 5 (RP2350_FAST_CODE on `imuMahonyAHRSupdate`, `imuCalculateEstimatedAttitude`). + +### Drill-down profiling (multi-file early-return, 1 kHz, no GPS, no angle mode) + +**IMU block (+308 µs) breakdown:** + +| Function | Cost | Notes | +|---|---|---| +| `imuUpdateAccelerometer()` | ~21 µs | Fast; just scales ADC samples | +| `imuUpdateAttitude()` (Mahony AHRS) | ~287 µs | **All of the IMU cost; runs from QSPI flash** | + +Sub-breakdown of `imuUpdateAttitude` (287 µs total): + +| Section | Cost | Notes | +|---|---|---| +| `gyroGetMeasuredRotationRate()` | ~1 µs | Trivial | +| `accGetMeasuredAcceleration()` + `imuCheckVibrationLevels()` | ~14 µs | Data reads + scaling | +| `imuCalculateFilters()` | ~5 µs | 9× `pt1FilterApply4` (already FAST_CODE, callee is in SRAM) | +| GPS/weight-calc overhead | ~0 µs | All GPS branches skip; weight math tiny | +| **`imuMahonyAHRSupdate()`** | **~205 µs** | **Quaternion integrator, ~2 KB, runs from QSPI flash — primary TODO 5 target** | +| **`imuUpdateEulerAngles()`** | **~62 µs** | **Calls `atan2_approx` × 2 + `acos_approx` × 1 from flash — also needs RP2350_FAST_CODE** | + +→ `imuMahonyAHRSupdate` (205 µs) + `imuUpdateEulerAngles` (62 µs) = 267 µs = 92% of the IMU block. + Both run from QSPI flash. Moving them to SRAM (TODO 5) should cut IMU cost to ~20 µs. + Estimated new PID avg: 683 - 267 ≈ **416 µs** (39% faster). + +→ `imuUpdateAttitude` alone is ~42% of the entire PID loop. TODO 5 is confirmed #1 priority. + +**Nav block (+115 µs) breakdown — inside `updatePositionEstimator()`:** + +| Function | Cost | Notes | +|---|---|---| +| `updateIMUTopic()` | ~64 µs | IMU pre-processing for nav; runs from flash | +| `updateEstimatedTopic()` | ~15 µs | State estimation step | +| `publishEstimatedTopic()` | ~32 µs | Write nav state to consumers | +| `applyWaypointNavigationAndAltitudeHold()` | ~0 µs | Essentially free without GPS | + +→ `updateIMUTopic` is the dominant nav cost. Possible second-core candidate: it runs + at PID rate but is independent of the RC/PID pipeline; it produces results consumed by + `updateEstimatedTopic`. Would need a double-buffer and spin-lock. Note for later. + +**PID computation block (+134 µs) breakdown — inside `pidController()`:** + +| Section | Cost | Notes | +|---|---|---| +| Rate-target setup loop (3 axes) | ~115 µs | `pidController` is FAST_CODE but calls some non-FAST_CODE helpers | +| Angle/horizon loop + turn assist | ~0 µs | Mode not active in bench test | +| Core PID loop (`pidControllerApplyFn` × 3) | ~35 µs | Callee fns are FAST_CODE; relatively cheap | + +→ Rate-target loop is expensive (~115 µs) despite `pidController` being in SRAM. + Likely culprits: `pidHeadingHold`, `adaptiveFilterPushRate`, `gyroKalmanUpdateSetpoint` + (conditional on target features) — these are not FAST_CODE and cause XIP cache pressure. + Check with `grep -r "USE_ADAPTIVE_FILTER\|USE_GYRO_KALMAN" src/main/target/RP2350_PICO/`. + +--- + +## TODO 1 — Map FAST_CODE to RAM (.time_critical) for RP2350 + +**Why:** On STM32F7/H7, `FAST_CODE` places hot functions in ITCM RAM (zero wait state). +On RP2350, `FAST_CODE` is currently a no-op (common.h only defines it for F7/H7). +The RP2350 executes all code from QSPI flash via a 16 KB XIP cache; cache-miss latency +on the large PID+scheduler+gyro code path is responsible for PID's 1464 µs avg. + +**Linker script note:** `rp2350_flash.ld` has `*(.time_critical*)` in TWO places: +- Line 74: inside `.text` section → FLASH only (bad — symbols stay in flash) +- Line 169: inside `.data` section (`> RAM AT> FLASH`) → copied to SRAM at boot (good) + +GNU ld matches each input section once, so the `.text` pattern at line 74 wins and +`.time_critical*` ends up in flash. **Fix:** remove `*(.time_critical*)` from `.text` +(line 74) so the `.data` rule at line 169 takes effect and copies them to SRAM. + +**Implementation steps:** +1. `rp2350_flash.ld` line 74: remove `*(.time_critical*)` from `.text` section. +2. `target.h` for RP2350: add after all other defines: + ```c + // FAST_CODE: place hot functions in SRAM (copied from flash at boot) to avoid + // XIP cache pressure. Overrides the no-op definition in common.h. + #undef FAST_CODE + #define FAST_CODE __attribute__((section(".time_critical.inav"))) + ``` + NOTE: common.h defines FAST_CODE without `#ifndef` guard so `#undef` first is needed. + target.h is included after common.h in the build chain. +3. Build and check map file: `grep time_critical build_rp2350/bin/RP2350_PICO.elf.map` + — should show scheduler.c, gyro.c, pid.c symbols in `.data` (RAM) not `.text`. +4. Measure TASK_PID avg/max before vs after via Configurator task tab or: + ``` + python3 debug/openocd_helper.py flash # flash new build + ``` + Expected: PID avg drops from ~1464 µs to ~300–500 µs (3–5× improvement). + +**Affected functions marked FAST_CODE:** scheduler(), taskGyro(), pidController(), +gyroUpdate(), and anything in scheduler.c/gyro.c/pid.c tagged FAST_CODE or NOINLINE. +`grep -r "FAST_CODE" src/main/` to get the full list. + +--- + +## TODO 2 — Test removing the gyro rate override in fc_tasks.c + +**Result:** Confirmed removable. With FAST_CODE + 192 MHz, GYRO averages 18 µs +(max 80 µs) — well within any reasonable period. No starvation without the block. + +PID still needs 1 kHz explicitly: the default looptime (500 µs) causes 86% avg +system load at 2 kHz; GPS/nav tasks would push it over the edge. Handled by TODO 3. + +**Status: DONE** ✓ — `#ifdef RP2350` block removed from `fc_tasks.c`. + +--- + +## TODO 3 — Loop rate 1 kHz via targetConfiguration (clean-up) + +Set `gyroConfigMutable()->looptime = 1000` in `targetConfiguration()` in +`src/main/target/RP2350_PICO/config.c`. Both tasks now use the standard +`getLooptime()` / `getGyroLooptime()` path in `fcTasksInit()`. + +Result: PID 993 Hz (39% avg load), GYRO 1088 Hz at natural rate, total 47% avg — +identical behaviour to the old `#ifdef` approach without the non-standard override. + +**Status: DONE** ✓ + +--- + +## TODO 4 — Flash script convenience + +Permanent flash script: `debug/flash.sh` (already created). +Usage: `./debug/flash.sh` from the RP2350_PICO target directory. +Flashes `build_rp2350/bin/RP2350_PICO.elf` via SWD (no BOOTSEL required). + +--- + +## TODO 5 — RP2350_FAST_CODE macro for large hot functions + +**Why:** `FAST_CODE` on all targets shares the F7 ITCM budget (16 KB, ~5 KB was free +before the RP2350 port). Large functions like `imuMahonyAHRSupdate` (~2 KB) and +`imuCalculateEstimatedAttitude` (~1 KB) would overflow F7 ITCM if marked `FAST_CODE`. +Those functions were intentionally left without `FAST_CODE` to keep the all-targets +budget intact, but they are the dominant XIP cache-pressure source on RP2350. + +**Solution:** define a `RP2350_FAST_CODE` macro that maps to `FAST_CODE` on RP2350 +only (and is a no-op everywhere else). Depends on TODO 1 (FAST_CODE → .time_critical). + +**Implementation:** +1. In `src/main/target/RP2350_PICO/target.h`, after the `FAST_CODE` override: + ```c + #define RP2350_FAST_CODE FAST_CODE + ``` +2. In all other target builds (or common.h), add: + ```c + #ifndef RP2350_FAST_CODE + #define RP2350_FAST_CODE + #endif + ``` +3. Mark the following functions `RP2350_FAST_CODE` in their definitions: + + **Primary targets (confirmed by drill-down profiling):** + - `imuMahonyAHRSupdate` (~2,080 B) — **205 µs**, quaternion integrator, called every PID cycle + - `imuUpdateEulerAngles` — **62 µs**, calls `atan2_approx`×2 + `acos_approx`×1 from flash + - `imuCalculateEstimatedAttitude` (~988 B) — wrapper for both above, called every PID cycle + + **Callee chain for `imuUpdateEulerAngles` (also need RP2350_FAST_CODE):** + - `atan2_approx`, `acos_approx` in `maths.c` — currently no-op (were stripped of FAST_CODE); + once `imuUpdateEulerAngles` is RP2350_FAST_CODE they become SRAM→flash veneer calls + + **Lower priority (skipped without GPS on bench test):** + - `imuCalculateGPSacceleration`, `imuCalculateTurnRateacceleration` (~360 B, ~244 B) + - `imuCalculateMcCogWeight`, `imuCalculateMcCogAccWeight` (~168 B, ~108 B) + - `processPilotAndFailSafeActions` in fc_core.c (~900 B, called every PID cycle) + +4. Build for both RP2350_PICO and an F7 target (e.g., JHEMCUF405); confirm F7 ITCM + size does not increase (map file `.itcm` / `d_itcm` section unchanged). + +**RP2350_FAST_CODE vs #ifdef FAST_CODE:** Use the macro. `#ifdef RP2350` in function +signatures is ugly and doesn't scale; a `RP2350_FAST_CODE` macro keeps the intent +visible at the definition site and degrades gracefully on all other targets to a no-op. + +**Measured result (commit 49ad7209):** +- PID avg: 710 µs → 575 µs (-135 µs, 19% improvement) +- PID max: 1401 µs → 1093 µs +- Smaller than the theoretical 267 µs; remaining gap likely due to callee functions + not yet in SRAM (see rate-target loop, `imuCheckAndResetOrientationQuaternion`, etc.) + +**Follow-up (see TODO 9):** `processPilotAndFailSafeActions`, `throttleStickMixedValue`, +`rcLookupThrottle` subsequently marked `RP2350_FAST_CODE` → 575 µs → 546 µs (-29 µs). + +**Status: DONE** ✓ — `RP2350_FAST_CODE` macro implemented; all listed functions marked. + +--- + +## TODO 10 — Set default clock to 192 MHz + +**Why:** The RP2350 supports up to 200+ MHz with default SoC configuration. At 192 MHz +vs 150 MHz default that is a 28% raw clock increase, which directly reduces the µs cost +of every instruction. Code that is already in SRAM benefits fully (no XIP factor). +XIP-resident code also benefits because the QSPI clock scales proportionally. + +**Implementation:** Call `set_sys_clock_khz(192000, true)` at the top of `systemInit()` +in `system_rp2350.c`, before `tusb_init()` and `stdio_init_all()`. Update the initial +`SystemCoreClock` constant from 150000000 to 192000000. + +The USB PLL is independent (clk_usb stays at 48 MHz from pll_usb) so TinyUSB CDC is +unaffected. The hardware timer (clk_timer, from clk_ref at 12 MHz) is also independent, +so `micros()` stays accurate. + +**Measured result:** +- PID avg: 503 µs → 360 µs (-143 µs, -28%) +- PID max: 1181 µs → 833 µs +- Better than theoretical 503 × (150/192) = 393 µs; SRAM-resident code benefits + extra since it has zero cache-miss penalty at any clock speed. + +**Cumulative from 710 µs baseline: 360 µs (-350 µs, -49%)** + +**Status: DONE** ✓ + +--- + +## TODO 11 — RP2350_FAST_CODE for updatePositionEstimator hot path + +**Why:** `updatePositionEstimator` runs every 1 kHz PID cycle from QSPI flash. +Drill-down profiling showed it costs ~115 µs total: + - `updateIMUTopic` (~65 µs): body frame → earth frame accel transform + calibration + - `updateEstimatedTopic` (~20 µs): EKF-style state estimation step + - `publishEstimatedTopic` (~30 µs of slot, but timer-gated at ~50 Hz — not full cost) + +**Implementation:** Mark `RP2350_FAST_CODE`: +- `updatePositionEstimator` in `navigation_pos_estimator.c` — tiny wrapper, 76 B +- `updateIMUTopic` — dominant cost, 692 B +- `updateIMUEstimationWeight` — callee of above, 236 B +- `updateEstimatedTopic` — second-largest nav cost, 1324 B +- `imuTransformVectorBodyToEarth` in `imu.c` — hot callee of updateIMUTopic, 48 B + +Note: `publishEstimatedTopic` (992 B) was skipped — its body only runs at 50 Hz +(timer-gated), so XIP pressure from it is negligible at 1 kHz. + +**Measured result:** +- PID avg: 546 µs → 503 µs (-43 µs, -8%) +- PID max: 1055 µs → 1181 µs (max is noisy; avg is the reliable metric) + +**Status: DONE** ✓ + +--- + +## TODO 9 — RP2350_FAST_CODE for pilot/throttle hot path + +**Why:** `processPilotAndFailSafeActions` runs every PID cycle (1 kHz) from QSPI flash. +Its hot callees `throttleStickMixedValue` and `rcLookupThrottle` are also in flash. +At 575 µs baseline, these account for an estimated 30–40 µs of cache-miss overhead. + +**Implementation:** Mark the following `RP2350_FAST_CODE`: +- `processPilotAndFailSafeActions` in `fc_core.c` — the per-cycle wrapper +- `throttleStickMixedValue` in `rc_controls.c` — throttle mix, called every cycle +- `rcLookupThrottle` in `rc_curves.c` — table lookup callee of `throttleStickMixedValue` + +Note: `applyRateDynamics` and `getAxisRcCommand` are already `FAST_CODE` (in SRAM). + +**Measured result:** +- PID avg: 575 µs → 546 µs (-29 µs) +- PID max: 1093 µs → 1055 µs + +**Status: DONE** ✓ + +--- + +## TODO 6 — Eliminate unnecessary sqrt in calc_length_pythagorean_3D call sites + +**Status: DONE** ✓ + +- `acceleration.c`: renamed `maxG` → `maxGSq`; `updateAccExtremes()` (1 kHz hot path) + now uses `sq(x)+sq(y)+sq(z)` comparison. `accGetMeasuredMaxG()` calls `fast_fsqrtf()` + only when OSD/MSP reads the value. +- `wind_estimator.c`: replaced two `calc_length_pythagorean_3D` calls with squared-norm + arithmetic. Sanity check is now `windSq < sq(fast_fsqrtf(prevWindSq) + 4000)`, + eliminating one sqrt entirely. + +Result: PID avg 369 µs → 322 µs (-47 µs, -13%). Cumulative from 710 µs baseline: **322 µs (-55%)**. + +--- + +## TODO 8 — Mark imuComputeRotationMatrix RP2350_FAST_CODE + +**Status: DONE** ✓ (already applied alongside TODO 5 changes; `imu.c:139` has `RP2350_FAST_CODE`) + +--- + +## TODO 7 — Architecture / Code Review + +**Status: DONE** ✓ + +Fixes applied (commit below): +- `serial_usb_vcp_rp2350.c`: removed blocking spin-loop from `usbVcpRead()`; callers + must check `serialRxBytesWaiting() > 0` before calling `serialRead()`. +- `system_rp2350.c`: removed `debugBlink()` function (caused 1.5 s boot delay); + pre-init PICO_RUNTIME_INIT blinks gated behind `#ifdef RP2350_DIAG_BLINK`. +- `system_rp2350.c`: checked `add_repeating_timer_ms()` return value. +- `system_rp2350.c`: replaced two-loop `getUniqueId()` with `memcpy` + `memset`. +- `io_rp2350.c`: `IO_GPIOPortIdx()` now returns `IO_Pin(io) >> 4` (port 1 for GPIO 16+). +- `imu.c`: `prevOrientation` snapshot interval reduced 100 → 10 cycles (100 ms → 10 ms). +- `tusb_config.h`: added TinyUSB version note to the OPT_MCU_RP2040 comment. + +--- + +## Completed + +- [x] USB VCP driver (`serial_usb_vcp_rp2350.c`) — TinyUSB CDC +- [x] `tusb_init()` + 1 ms repeating timer for `tud_task()` in `system_rp2350.c` +- [x] `USE_VCP`, `SERIAL_PORT_COUNT=3` in target.h +- [x] Scheduler starvation root cause found (GYRO exec > period → forcedRealTimeTask) +- [x] Gyro/PID rate override in fc_tasks.c (2000 µs / 500 Hz) +- [x] Dynamic notch filter disabled in targetConfiguration() (config.c) +- [x] M4: Configurator connects, shows board name + firmware version + sensor status diff --git a/src/main/target/RP2350_PICO/config.c b/src/main/target/RP2350_PICO/config.c new file mode 100644 index 00000000000..1de90882c4a --- /dev/null +++ b/src/main/target/RP2350_PICO/config.c @@ -0,0 +1,38 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include + +#include "config/config_master.h" +#include "sensors/gyro.h" + +void targetConfiguration(void) +{ +#ifdef USE_DYNAMIC_FILTERS + // Disable dynamic notch filter by default (performance optimization for wing) + // This board is performance-constrained and wing aircraft typically don't need + // dynamic notch filtering (designed for multirotor motor noise) + gyroConfigMutable()->dynamicGyroNotchEnabled = 0; +#endif + + // Run PID at 1 kHz. The RP2350 PID loop averages ~360 µs at 192 MHz; the + // 500 µs default looptime leaves insufficient headroom when GPS/nav tasks + // are active. 1000 µs gives comfortable margin without affecting control + // quality (INAV's fixed-wing tuning is designed for 1 kHz). + gyroConfigMutable()->looptime = 1000; +} diff --git a/src/main/target/RP2350_PICO/debug/openocd_helper.py b/src/main/target/RP2350_PICO/debug/openocd_helper.py new file mode 100644 index 00000000000..7f24d91fc52 --- /dev/null +++ b/src/main/target/RP2350_PICO/debug/openocd_helper.py @@ -0,0 +1,213 @@ +#!/usr/bin/env python3 +""" +OpenOCD telnet helper for RP2350 SWD debugging. + +Usage examples: + python3 openocd_helper.py sample_pc # Sample PC 5 times + python3 openocd_helper.py check_fault # Read CFSR/BFAR/PC after halt + python3 openocd_helper.py check_stack # Halt + dump registers + stack + python3 openocd_helper.py set_bp 0x10001234 # Set breakpoint + resume + python3 openocd_helper.py flash # Flash ELF via SWD (no BOOTSEL) + +Requires OpenOCD already running, or launches it automatically. + +Tested with: + OOCD = ~/.pico-sdk/openocd/0.12.0+dev/openocd + Target: RP2350 (Pico 2) via debugprobe (Pico as CMSIS-DAP, VID:PID 2e8a:000c) + SWD wiring: debugprobe GP2->SWCLK, GP3->SWDIO on target +""" + +import socket +import time +import subprocess +import sys +import os + +OOCD = os.path.expanduser("~/.pico-sdk/openocd/0.12.0+dev/openocd") +SCRIPTS = os.path.expanduser("~/.pico-sdk/openocd/0.12.0+dev/scripts") +ELF = os.path.expanduser( + "~/Documents/planes/inavflight/inav/build_rp2350/bin/RP2350_PICO.elf" +) + + +def start_openocd(): + proc = subprocess.Popen( + [OOCD, "-s", SCRIPTS, + "-f", "interface/cmsis-dap.cfg", + "-f", "target/rp2350.cfg", + "-c", "adapter speed 5000", + "-c", "init"], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + ) + time.sleep(3) + return proc + + +def connect(): + s = socket.socket() + s.connect(("127.0.0.1", 4444)) + time.sleep(0.5) + s.recv(4096) # discard banner + return s + + +def cmd(s, c, delay=0.5): + s.sendall((c + "\n").encode()) + time.sleep(delay) + r = b"" + s.settimeout(0.4) + try: + while True: + chunk = s.recv(4096) + if not chunk: + break + r += chunk + except Exception: + pass + return r.decode(errors="replace") + + +def nm_lookup(addrs): + """Return {addr: funcname} for a list of PC values.""" + result = {} + try: + syms = [] + out = subprocess.check_output( + ["arm-none-eabi-nm", ELF], stderr=subprocess.DEVNULL + ).decode() + for line in out.splitlines(): + parts = line.strip().split() + if len(parts) >= 3 and parts[1].upper() in ("T", "t"): + syms.append((int(parts[0], 16), parts[2])) + syms.sort() + for t in addrs: + for i, (addr, name) in enumerate(syms): + if addr > t: + prev = syms[i - 1] + result[t] = f"{name} (+0x{t - prev[0]:x})" + break + except Exception as e: + print(f"nm lookup failed: {e}") + return result + + +# ── commands ────────────────────────────────────────────────────────────────── + +def sample_pc(n=5): + proc = start_openocd() + s = connect() + pcs = [] + for _ in range(n): + cmd(s, "halt", 0.3) + r = cmd(s, "reg pc", 0.3) + for line in r.splitlines(): + if "pc (/32)" in line: + pcs.append(int(line.split(":")[1].strip(), 16)) + cmd(s, "resume", 0.3) + time.sleep(0.5) + cmd(s, "shutdown", 0.3) + proc.wait(timeout=5) + + names = nm_lookup(pcs) + for pc in pcs: + print(f" 0x{pc:08x} {names.get(pc, '?')}") + + +def check_fault(): + """Halt and read fault status registers + exception frame.""" + proc = start_openocd() + s = connect() + + print(cmd(s, "halt")) + print("PC:", cmd(s, "reg pc")) + print("SP:", cmd(s, "reg sp")) + print("LR:", cmd(s, "reg lr")) + + # Fault status + cfsr_raw = cmd(s, "mdw 0xe000ed28") # CFSR + hfsr_raw = cmd(s, "mdw 0xe000ed2c") # HFSR + bfar_raw = cmd(s, "mdw 0xe000ed38") # BFAR + print("CFSR:", cfsr_raw) + print("HFSR:", hfsr_raw) + print("BFAR:", bfar_raw) + + # Exception frame: INAV HardFault handler pushes {r7,lr}+sub sp,#8 → frame at SP+16 + sp_r = cmd(s, "reg sp") + for line in sp_r.splitlines(): + if "sp (/32)" in line: + sp = int(line.split(":")[1].strip(), 16) + frame = sp + 16 + print(f"\nException frame at 0x{frame:08x}:") + print(cmd(s, f"mdw 0x{frame:08x} 8")) + # frame+24 = faulting PC + fpc_raw = cmd(s, f"mdw 0x{frame + 24:08x}") + print("Faulting PC word:", fpc_raw) + for w in fpc_raw.split(): + try: + fpc = int(w, 16) + if 0x10000000 <= fpc <= 0x10400000: + names = nm_lookup([fpc]) + print(f" -> {names.get(fpc, '?')}") + except ValueError: + pass + break + + cmd(s, "shutdown", 0.3) + proc.wait(timeout=5) + + +def check_stack(): + """Halt and dump registers + top of stack.""" + proc = start_openocd() + s = connect() + + print(cmd(s, "halt")) + for reg in ("pc", "sp", "lr", "r0", "r1"): + print(cmd(s, f"reg {reg}")) + + sp_r = cmd(s, "reg sp") + for line in sp_r.splitlines(): + if "sp (/32)" in line: + sp = int(line.split(":")[1].strip(), 16) + print(f"Stack top (sp=0x{sp:08x}, 16 words):") + print(cmd(s, f"mdw 0x{sp:08x} 16")) + break + + # CFSR + print("CFSR:", cmd(s, "mdw 0xe000ed28")) + print("BFAR:", cmd(s, "mdw 0xe000ed38")) + + cmd(s, "shutdown", 0.3) + proc.wait(timeout=5) + + +def flash_elf(elf_path=None): + """Flash ELF via SWD — no BOOTSEL mode required.""" + elf = elf_path or ELF + result = subprocess.run( + [OOCD, "-s", SCRIPTS, + "-f", "interface/cmsis-dap.cfg", + "-f", "target/rp2350.cfg", + "-c", "adapter speed 5000", + "-c", f"program {elf} verify reset exit"], + ) + return result.returncode == 0 + + +# ── main ────────────────────────────────────────────────────────────────────── + +if __name__ == "__main__": + op = sys.argv[1] if len(sys.argv) > 1 else "sample_pc" + if op == "sample_pc": + sample_pc(int(sys.argv[2]) if len(sys.argv) > 2 else 5) + elif op == "check_fault": + check_fault() + elif op == "check_stack": + check_stack() + elif op == "flash": + ok = flash_elf(sys.argv[2] if len(sys.argv) > 2 else None) + sys.exit(0 if ok else 1) + else: + print(__doc__) + sys.exit(1) diff --git a/src/main/target/RP2350_PICO/pico/version.h b/src/main/target/RP2350_PICO/pico/version.h new file mode 100644 index 00000000000..6eb95862e98 --- /dev/null +++ b/src/main/target/RP2350_PICO/pico/version.h @@ -0,0 +1,15 @@ +/* + * Pico SDK version header — normally auto-generated by CMake. + * Provided manually for INAV RP2350 build. + * SDK version: 2.1.0 + */ + +#ifndef _PICO_VERSION_H +#define _PICO_VERSION_H + +#define PICO_SDK_VERSION_MAJOR 2 +#define PICO_SDK_VERSION_MINOR 1 +#define PICO_SDK_VERSION_REVISION 0 +#define PICO_SDK_VERSION_STRING "2.1.0" + +#endif diff --git a/src/main/target/RP2350_PICO/pico_sdk_config.h b/src/main/target/RP2350_PICO/pico_sdk_config.h new file mode 100644 index 00000000000..37756454d7e --- /dev/null +++ b/src/main/target/RP2350_PICO/pico_sdk_config.h @@ -0,0 +1,52 @@ +/* + * INAV RP2350 Pico SDK Configuration + * + * Replaces the auto-generated pico/config_autogen.h. + * Referenced via -DPICO_CONFIG_HEADER=pico_sdk_config.h + * + * Platform defines (PICO_RP2350, PICO_RP2350A, etc.) are set via + * cmake compiler flags in cmake/rp2350.cmake. + */ + +#ifndef _INAV_PICO_SDK_CONFIG_H +#define _INAV_PICO_SDK_CONFIG_H + +// Board identifier +#define PICO_BOARD "pico2" + +// SDK library flags — tells SDK which components are available +#define LIB_CMSIS_CORE 1 +#define LIB_PICO_PLATFORM_PANIC 1 +#define LIB_PICO_STDIO 1 +#define LIB_PICO_STDIO_USB 1 +#define LIB_PICO_PRINTF 1 +#define LIB_PICO_PRINTF_PICO 1 +#define LIB_PICO_RUNTIME 1 +#define LIB_PICO_RUNTIME_INIT 1 +#define LIB_PICO_STANDARD_BINARY_INFO 1 +#define LIB_PICO_SYNC 1 +#define LIB_PICO_TIME 1 +#define LIB_PICO_UTIL 1 +#define LIB_PICO_MALLOC 0 +#define LIB_PICO_MEM_OPS 0 +#define LIB_PICO_ATOMIC 1 +#define LIB_PICO_MULTICORE 0 +#define LIB_PICO_BOOTROM 1 +#define LIB_PICO_STDLIB 1 + +// USB CDC configuration +#define PICO_STDIO_USB_CONNECT_WAIT_TIMEOUT_MS 0 +#define PICO_RP2040_USB_DEVICE_ENUMERATION_FIX 0 +#define PICO_RP2040_USB_DEVICE_UFRAME_FIX 0 + +// No C++ exceptions +#define PICO_CXX_ENABLE_EXCEPTIONS 0 + +// Mem ops — use compiler builtins +#define PICO_USE_OPTIMIZED_ROM_MEMSET 0 +#define PICO_USE_OPTIMIZED_ROM_MEMCPY 0 + +// CMSIS rename exceptions (maps SDK IRQ names to CMSIS names) +#include "cmsis/rename_exceptions.h" + +#endif /* _INAV_PICO_SDK_CONFIG_H */ diff --git a/src/main/target/RP2350_PICO/target.c b/src/main/target/RP2350_PICO/target.c new file mode 100644 index 00000000000..d8ce0edc917 --- /dev/null +++ b/src/main/target/RP2350_PICO/target.c @@ -0,0 +1,102 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include + +#include +#include "target.h" + +#include "common/utils.h" +#include "drivers/io.h" +#include "drivers/system.h" +#include "drivers/pwm_mapping.h" +#include "drivers/pwm_output.h" +#include "drivers/timer.h" +#include "drivers/serial.h" +#include "drivers/serial_uart.h" +#include "drivers/serial_uart_impl.h" + +/* + * Output mapping table — 10 GPIO pins in 5 slice groups. + * + * All entries use TIM_USE_OUTPUT_AUTO so pwmMotorAndServoInit() assigns + * them as motors or servos based on getMotorCount() and any + * timerOverrides() the user has set in the Configurator. + * + * Field order matches timerHardware_t (non-AT32 build): + * tim, tag, channelIndex, output, ioMode, alternateFunction, usageFlags, dmaTag + * + * Port A (gpioid 0) = GPIO 0–15; Port B (gpioid 1) = GPIO 16–29. + * GP8 = PA8 GP9 = PA9 GP10 = PA10 GP11 = PA11 + * GP12 = PA12 GP13 = PA13 GP14 = PA14 GP15 = PA15 (dual-use: UART3/4) + * GP20 = PB4 GP21 = PB5 + * GP16-19 are reserved: Flash CS (GP16), Beeper (GP17), I2C1 SDA/SCL (GP18/19). + */ +timerHardware_t timerHardware[] = { + /* slice 4 — motor group (GP8/GP9) */ + DEF_TIM(TIM4, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), /* GP8 */ + DEF_TIM(TIM4, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 0), /* GP9 */ + /* slice 5 — motor group (GP10/GP11) */ + DEF_TIM(TIM5, CH1, PA10, TIM_USE_OUTPUT_AUTO, 0, 0), /* GP10 */ + DEF_TIM(TIM5, CH2, PA11, TIM_USE_OUTPUT_AUTO, 0, 0), /* GP11 */ + /* slice 6 — servo group (GP12/GP13; dual-use with UART3 TX/RX on PIO1) */ + DEF_TIM(TIM6, CH1, PA12, TIM_USE_OUTPUT_AUTO, 0, 0), /* GP12 */ + DEF_TIM(TIM6, CH2, PA13, TIM_USE_OUTPUT_AUTO, 0, 0), /* GP13 */ + /* slice 7 — servo group (GP14/GP15; dual-use with UART4 TX/RX on PIO1) */ + DEF_TIM(TIM7, CH1, PA14, TIM_USE_OUTPUT_AUTO, 0, 0), /* GP14 */ + DEF_TIM(TIM7, CH2, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), /* GP15 */ + /* slice 10 — servo group (GP20/GP21; dedicated, GP16-19 reserved) */ + DEF_TIM(TIM10, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), /* GP20 */ + DEF_TIM(TIM10, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), /* GP21 */ +}; +const int timerHardwareCount = 10; + +void failureMode(failureMode_e mode) +{ + UNUSED(mode); + while (1) {} +} + +bool isMPUSoftReset(void) +{ + return false; +} + +// UART dispatch — hardware UARTs 1-2 via RP2350 PL011, PIO UARTs 3-4 via PIO1 +serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, + void *rxCallbackData, uint32_t baudRate, + portMode_t mode, portOptions_t options) +{ + uartPort_t *s = NULL; + if (USARTx == USART1) { s = serialUART1(baudRate, mode, options); } + else if (USARTx == USART2) { s = serialUART2(baudRate, mode, options); } + else if (USARTx == USART3) { s = serialUART3(baudRate, mode, options); } + else if (USARTx == USART4) { s = serialUART4(baudRate, mode, options); } + if (!s) { return NULL; } + s->port.rxCallback = rxCallback; + s->port.rxCallbackData = rxCallbackData; + return (serialPort_t *)s; +} diff --git a/src/main/target/RP2350_PICO/target.h b/src/main/target/RP2350_PICO/target.h new file mode 100644 index 00000000000..8768aff6820 --- /dev/null +++ b/src/main/target/RP2350_PICO/target.h @@ -0,0 +1,184 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "RP2P" +#define USBD_PRODUCT_STRING "RP2350_PICO" + +#define LED0 PB9 // GPIO 25 (Port B pin 9) + +// GPIO port mapping for RP2350: +// Port A (gpioid 0) = GPIO 0-15 +// Port B (gpioid 1) = GPIO 16-29 +#define TARGET_IO_PORTA 0xFFFF +#define TARGET_IO_PORTB 0x3FFF + +// Flash-based config storage in FLASH_CONFIG region (0x103F0000, 64 KB) +// __config_start / __config_end are defined in rp2350_flash.ld. +#define CONFIG_IN_FLASH +#define EEPROM_SIZE 32768 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 + +#define SERIAL_PORT_COUNT 5 // VCP + UART1 + UART2 + UART3 + UART4 + +// DShot motor output via PIO0 (1 SM per motor, up to 4 motors). +// GP8–11 default to motors 1–4; GP4–7 are reserved for SPI0 (gyro + flash). +// Motor/servo GPIO assignments come from timerHardware[] in target.c. + +// Servo PWM output via hardware PWM slices (GP16–GP19 by default). +// 50 Hz, 1000–2000 µs pulse width. GP16–19 are free from other peripherals. + +// ADC inputs are hardware-fixed on RP2350A: ADC0–3 map only to GPIO26–29. +// ADC_CHANNEL_N_PIN cannot be changed without a board respin. +#define ADC_CHANNEL_1_PIN PB10 /* GPIO 26 — battery voltage */ +#define ADC_CHANNEL_2_PIN PB11 /* GPIO 27 — current sensor */ +#define ADC_CHANNEL_3_PIN PB12 /* GPIO 28 — RSSI voltage */ + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define USE_DSHOT + +/* + * Hardware UART pin assignments for Raspberry Pi Pico 2 — Option C layout. + * + * UART1 (INAV) → RP2350 uart0: GP0/1 + * UART2 (INAV) → RP2350 uart1: GP2/3 + * UART3 (INAV) → PIO1 SM0(TX)+SM1(RX): GP12/13 + * UART4 (INAV) → PIO1 SM2(TX)+SM3(RX): GP14/15 + * + * GP4–7 are reserved for SPI0 (gyro + flash, future M5/M6). + * GP8–11 are reserved for DShot motors on PIO0 (future M8). + * PIO2 SM0 is reserved for WS2812 LED strip; SMs 1–3 spare. + */ +#define UART1_TX_PIN PA0 /* GPIO0 — uart0 TX (MSP / configurator) */ +#define UART1_RX_PIN PA1 /* GPIO1 — uart0 RX */ +#define UART2_TX_PIN PA2 /* GPIO2 — uart1 TX (receiver: CRSF/SBUS) */ +#define UART2_RX_PIN PA3 /* GPIO3 — uart1 RX (HW inversion, no external inverter) */ +/* PIO1: UART3 on SM0(TX)+SM1(RX), UART4 on SM2(TX)+SM3(RX) */ +/* PIO2 is reserved for RGB LED strip (SM0) and future UART5/6 (SMs 1–3) */ +#define UART3_TX_PIN PA12 /* GPIO12 — PIO1 SM0 TX (GPS) */ +#define UART3_RX_PIN PA13 /* GPIO13 — PIO1 SM1 RX */ +#define UART4_TX_PIN PA14 /* GPIO14 — PIO1 SM2 TX (telemetry / extra) */ +#define UART4_RX_PIN PA15 /* GPIO15 — PIO1 SM3 RX */ + +#define DEFAULT_RX_FEATURE FEATURE_RX_MSP +#define DEFAULT_FEATURES (FEATURE_GPS | FEATURE_VBAT) + +#define USE_ADC +#define USE_IMU_FAKE +#define USE_BARO +#define USE_BARO_ALL +#define USE_GPS_FAKE +#define USE_PITOT_FAKE +#define USE_RANGEFINDER_FAKE +#define USE_RX_SIM + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SDA PB2 /* GPIO18 — i2c1 SDA */ +#define I2C1_SCL PB3 /* GPIO19 — i2c1 SCL */ +#define DEFAULT_I2C_BUS BUS_I2C1 +#define MAG_I2C_BUS DEFAULT_I2C_BUS +#define BARO_I2C_BUS DEFAULT_I2C_BUS + +#define USE_MAG +#define USE_MAG_ALL + +#define USE_MSP_OSD +#define USE_OSD + +#undef USE_DASHBOARD +#define USE_VCP +#undef USE_PPM +#undef USE_PWM +#define USE_LED_STRIP +#define WS2811_PIN PB6 /* GP22 — free from flash/I2C/UART/SPI */ +#define PIO_LEDSTRIP_INDEX 2 /* PIO2 SM0 — reserved for WS2812 */ +#undef USE_MSP_OVER_TELEMETRY +#undef USE_TELEMETRY_FRSKY_HUB +#undef USE_TELEMETRY_HOTT +#undef USE_TELEMETRY_SMARTPORT +#undef USE_RESOURCE_MGMT +#undef USE_TELEMETRY_CRSF +#undef USE_TELEMETRY_IBUS +#undef USE_TELEMETRY_JETIEXBUS +#undef USE_TELEMETRY_SRXL +#undef USE_TELEMETRY_GHST +#undef USE_VTX_TRAMP +#undef USE_CAMERA_CONTROL +#undef USE_BRUSHED_ESC_AUTODETECT +#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER +#undef USE_SERIAL_4WAY_SK_BOOTLOADER +#undef USE_ADAPTIVE_FILTER +#undef USE_GYRO_KALMAN + +// SPI0 — gyro + flash: GP4 (MISO/PA4), GP6 (SCK/PA6), GP7 (MOSI/PA7) +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA6 /* GPIO6 — spi0 SCK */ +#define SPI1_MISO_PIN PA4 /* GPIO4 — spi0 MISO */ +#define SPI1_MOSI_PIN PA7 /* GPIO7 — spi0 MOSI */ + +// FAST_CODE: place hot functions in SRAM (copied from flash at boot) to avoid +// XIP cache pressure on the large PID/scheduler/gyro code path. +// common.h defines FAST_CODE without a #ifndef guard, so we must #undef first. +// The linker script (rp2350_flash.ld) places .time_critical* in .data > RAM AT> FLASH +// so these symbols are automatically copied to SRAM by crt0 at boot. +#undef FAST_CODE +#define FAST_CODE __attribute__((section(".time_critical.inav"))) + +// RP2350_FAST_CODE: like FAST_CODE but only active on RP2350. +// Used for functions too large for F7 ITCM (e.g. imuMahonyAHRSupdate ~2 KB) +// that would overflow F7 ITCM if marked plain FAST_CODE. +#undef RP2350_FAST_CODE +#define RP2350_FAST_CODE FAST_CODE + +#define TARGET_FLASH_SIZE 4096 + +#define LED_STRIP_TIMER 1 +#define SOFTSERIAL_1_TIMER 2 +#define SOFTSERIAL_2_TIMER 3 + +/* RP2350 PWM slice "timers" — one TIM_TypeDef per slice, used as group IDs. + * Analogous to TIM1/TIM3/… on STM32; pins sharing a slice must run at the + * same update rate. Defined in drivers/timer_rp2350.c. */ +extern TIM_TypeDef rp2350Pwm4; /* slice 4: GP8/GP9 — motors 1-2 */ +extern TIM_TypeDef rp2350Pwm5; /* slice 5: GP10/GP11 — motors 3-4 */ +extern TIM_TypeDef rp2350Pwm6; /* slice 6: GP12/GP13 — servos (dual-use UART3) */ +extern TIM_TypeDef rp2350Pwm7; /* slice 7: GP14/GP15 — servos (dual-use UART4) */ +extern TIM_TypeDef rp2350Pwm10; /* slice 10: GP20/GP21 — servos (dedicated) */ + +/* On RP2350, TIMn = PWM slice n (slice = gpio / 2; A/B channels share clkdiv/wrap). + * GP8/9→slice4, GP10/11→slice5, GP12/13→slice6, GP14/15→slice7, GP20/21→slice10. */ +#define TIM4 (&rp2350Pwm4) +#define TIM5 (&rp2350Pwm5) +#define TIM6 (&rp2350Pwm6) +#define TIM7 (&rp2350Pwm7) +#define TIM10 (&rp2350Pwm10) diff --git a/src/main/target/RP2350_PICO/tusb_config.h b/src/main/target/RP2350_PICO/tusb_config.h new file mode 100644 index 00000000000..dbbe2867884 --- /dev/null +++ b/src/main/target/RP2350_PICO/tusb_config.h @@ -0,0 +1,41 @@ +/* + * TinyUSB configuration for INAV RP2350 USB CDC stdio + * + * Minimal config: CDC only (serial console for debug printf) + */ + +#ifndef _TUSB_CONFIG_H +#define _TUSB_CONFIG_H + +// MCU selection — OPT_MCU_RP2040 is correct for both RP2040 and RP2350 in +// TinyUSB 0.15/0.16 (shipped with Pico SDK 2.x). OPT_MCU_RP2350 was added +// in TinyUSB 0.17; update this when the SDK dependency is bumped. +#define CFG_TUSB_MCU OPT_MCU_RP2040 + +// USB device mode on rhport 0 — must be set so tusb_init() calls tud_init(0). +// Without this, TUD_OPT_RHPORT is undefined and tusb_init() skips tud_init, +// leaving the USB hardware controller disabled. +#define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE + +#define CFG_TUD_ENABLED 1 +#define CFG_TUH_ENABLED 0 + +// CDC class — one interface for stdio +#define CFG_TUD_CDC 1 +#define CFG_TUD_CDC_RX_BUFSIZE 256 +#define CFG_TUD_CDC_TX_BUFSIZE 256 + +// No other USB classes needed for M2 +#define CFG_TUD_MSC 0 +#define CFG_TUD_HID 0 +#define CFG_TUD_MIDI 0 +#define CFG_TUD_VENDOR 0 +#define CFG_TUD_DFU_RUNTIME 0 + +// Operating system abstraction — use Pico SDK +#define CFG_TUSB_OS OPT_OS_PICO + +// Use default endpoint size +#define CFG_TUD_ENDPOINT0_SIZE 64 + +#endif /* _TUSB_CONFIG_H */ diff --git a/src/main/target/common.h b/src/main/target/common.h index 45eb12ac4bc..3c3607a4d82 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -29,6 +29,12 @@ #define NOINLINE #endif +/* RP2350_FAST_CODE: marks large hot functions for SRAM placement on RP2350 only. + * These functions are too large for F7 ITCM (budget ~5 KB free before RP2350 port), + * so they cannot use plain FAST_CODE on all targets. Overridden to FAST_CODE by + * the RP2350_PICO target.h. No-op on all other targets. */ +#define RP2350_FAST_CODE + #define DYNAMIC_HEAP_SIZE 2048 #define I2C1_OVERCLOCK false diff --git a/src/main/target/link/rp2350_flash.ld b/src/main/target/link/rp2350_flash.ld new file mode 100644 index 00000000000..cacb359e3bd --- /dev/null +++ b/src/main/target/link/rp2350_flash.ld @@ -0,0 +1,267 @@ +/* + * Linker script for RP2350 (Raspberry Pi Pico 2) + * + * Compatible with both Pico SDK crt0.S and INAV sections. + * + * Memory layout: + * FLASH: 4032K XIP flash (0x10000000) + * FLASH_CONFIG: 64K settings storage (0x103F0000) + * RAM: 512K SRAM (0x20000000) + * SCRATCH_X: 4K core1 stack (0x20080000) + * SCRATCH_Y: 4K core0 stack (0x20081000) + */ + +MEMORY +{ + FLASH(rx) : ORIGIN = 0x10000000, LENGTH = 4032K + FLASH_CONFIG(r) : ORIGIN = 0x103F0000, LENGTH = 64K + RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 512K + SCRATCH_X(rwx) : ORIGIN = 0x20080000, LENGTH = 4K + SCRATCH_Y(rwx) : ORIGIN = 0x20081000, LENGTH = 4K +} + +ENTRY(_entry_point) + +/* Stack — SDK uses __StackTop/__StackLimit, INAV uses _estack */ +__StackTop = ORIGIN(RAM) + LENGTH(RAM); +_estack = __StackTop; + +/* Config storage */ +__config_start = ORIGIN(FLASH_CONFIG); +__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG); + +SECTIONS +{ + .flash_begin : { + __flash_binary_start = .; + } > FLASH + + /* Vector table — SDK crt0.S uses .vectors, followed by the picobin + IMAGE_DEF block that the RP2350 ROM bootloader requires to execute + the image. Without .embedded_block, the ROM stays in mass storage. */ + .text_boot : + { + __logical_binary_start = .; + KEEP (*(.vectors)) + KEEP (*(.binary_info_header)) + __binary_info_header_end = .; + KEEP (*(.embedded_block)) + __embedded_block_end = .; + } > FLASH + + /* SDK reset handler code */ + .reset : + { + KEEP(*(.reset)) + } > FLASH + + /* Optional stage-2 XIP setup function (not needed for normal flash boot + on RP2350, but must be <= 256 bytes if present) */ + .boot2 : + { + __boot2_start__ = .; + KEEP (*(.boot2)) + __boot2_end__ = .; + } > FLASH + + ASSERT(__boot2_end__ - __boot2_start__ <= 256, + "ERROR: boot2 XIP setup function must be no more than 256 bytes") + + /* Program code */ + .text : + { + . = ALIGN(4); + *(.text) + *(.text*) + *(.rodata) + *(.rodata*) + *(.glue_7) + *(.glue_7t) + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; + } > FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } > FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } > FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } > FLASH + + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } > FLASH + + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } > FLASH + + /* INAV parameter group registry */ + .pg_registry : + { + PROVIDE_HIDDEN (__pg_registry_start = .); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = .); + } > FLASH + + .pg_resetdata : + { + PROVIDE_HIDDEN (__pg_resetdata_start = .); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = .); + } > FLASH + + /* INAV bus device registry */ + .busdev_registry : + { + PROVIDE_HIDDEN (__busdev_registry_start = .); + KEEP (*(.busdev_registry)) + KEEP (*(SORT(.busdev_registry.*))) + PROVIDE_HIDDEN (__busdev_registry_end = .); + } > FLASH + + /* SDK binary info */ + .binary_info : + { + __binary_info_start = .; + KEEP(*(.binary_info.keep.*)) + __binary_info_end = .; + /* Pad to 4-byte boundary so that .data's LMA (= LOADADDR(.data)) is + 4-byte aligned. crt0.S copies .data with ldmia which requires + word-aligned addresses; a misaligned source triggers a HardFault. */ + . = ALIGN(4); + } > FLASH + + /* Initialized data — loaded from flash, runs from RAM. + SDK mutex_array goes here so mutex_t structs are copied to RAM at boot + and can be written by mutex_init(). Placing mutex_array in flash-only + would prevent mutex_init from storing the spin_lock pointer, leaving + spin_lock=NULL and causing an infinite spin on ROM address 0x00000000. */ + .data : + { + . = ALIGN(4); + _sdata = .; + __data_start__ = .; + *(.data) + *(.data*) + *(.time_critical*) + *(.after_data.*) + + . = ALIGN(4); + PROVIDE_HIDDEN (__mutex_array_start = .); + KEEP(*(SORT(.mutex_array.*))) + KEEP(*(.mutex_array)) + PROVIDE_HIDDEN (__mutex_array_end = .); + + . = ALIGN(4); + _edata = .; + __data_end__ = .; + } > RAM AT> FLASH + + /* __etext is (for backwards compatibility) the name of the .data init source pointer. + crt0.S uses __etext to find where to copy .data from — it must equal LOADADDR(.data), + NOT the end of .text (which comes earlier, before pg_registry/busdev_registry sections). */ + __etext = LOADADDR(.data); + _sidata = LOADADDR(.data); + + /* RAM interrupt vector table. + Cortex-M33 VTOR requires alignment to next power-of-2 >= table size. + RP2350 has 16 + 52 = 68 exceptions × 4 bytes = 272 bytes → 512-byte alignment. + Without this, the hardware clears VTOR[8:0] (shifts by -0x40), making + irq_set_exclusive_handler read the wrong entry and hard-assert. */ + .ram_vector_table (NOLOAD) : + { + . = ALIGN(512); + *(.ram_vector_table) + } > RAM + + /* Uninitialized data */ + . = ALIGN(4); + .bss (NOLOAD) : + { + _sbss = .; + __bss_start__ = _sbss; + *(.bss) + *(SORT_BY_ALIGNMENT(.bss*)) + /* INAV "fast RAM" BSS — no separate fast RAM on RP2350; flatten here so + crt0's __bss_start__/__bss_end__ loop zeros it like any other BSS. */ + *(.fastram_bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; + __bss_end__ = _ebss; + } > RAM + + /* Heap and stack check */ + _Min_Heap_Size = 0x400; + _Min_Stack_Size = 0x800; + + .heap (NOLOAD) : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + __end__ = .; + PROVIDE( __HeapLimit = __StackLimit ); + } > RAM + + /* Stack limit — checked by SDK malloc/sbrk for heap/stack collision */ + __StackLimit = __StackTop - _Min_Stack_Size; + + /* Scratch memory for multicore */ + .scratch_x : + { + __scratch_x_start__ = .; + *(.scratch_x.*) + . = ALIGN(4); + __scratch_x_end__ = .; + } > SCRATCH_X AT> FLASH + __scratch_x_source__ = LOADADDR(.scratch_x); + + .scratch_y : + { + __scratch_y_start__ = .; + *(.scratch_y.*) + . = ALIGN(4); + __scratch_y_end__ = .; + } > SCRATCH_Y AT> FLASH + __scratch_y_source__ = LOADADDR(.scratch_y); + + /* End picobin block — closes the block loop started by .embedded_block. + Must be at the end of flash so the ROM can find both ends. */ + .flash_end : { + KEEP(*(.embedded_end_block*)) + PROVIDE(__flash_binary_end = .); + } > FLASH =0xaa + + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/src/utils/elf2uf2.py b/src/utils/elf2uf2.py new file mode 100644 index 00000000000..6d2fa359cf1 --- /dev/null +++ b/src/utils/elf2uf2.py @@ -0,0 +1,78 @@ +#!/usr/bin/env python3 +""" +Convert ARM ELF (via objcopy .bin) to UF2 format for RP2350. + +Usage: elf2uf2.py [--base-addr 0x10000000] [--family-id 0xe48bff59] + +UF2 spec: https://github.com/microsoft/uf2 +""" + +import struct +import sys +import argparse + +UF2_MAGIC_START0 = 0x0A324655 # "UF2\n" +UF2_MAGIC_START1 = 0x9E5D5157 +UF2_MAGIC_END = 0x0AB16F30 +UF2_FLAG_FAMILY = 0x00002000 + +RP2350_FAMILY_ID = 0xe48bff59 +RP2350_FLASH_BASE = 0x10000000 +PAYLOAD_SIZE = 256 + + +def bin_to_uf2(data, base_addr, family_id): + blocks = [] + num_blocks = (len(data) + PAYLOAD_SIZE - 1) // PAYLOAD_SIZE + + for i in range(num_blocks): + offset = i * PAYLOAD_SIZE + chunk = data[offset:offset + PAYLOAD_SIZE] + # Pad last chunk if needed + chunk = chunk + b'\x00' * (PAYLOAD_SIZE - len(chunk)) + + # 32-byte header + header = struct.pack(' {args.output}: {len(uf2)} bytes ' + f'({len(uf2) // 512} UF2 blocks)') + + +if __name__ == '__main__': + main()