Skip to content

RP2350 (Pico 2) port — Milestone 1: Build system & empty target#45

Open
sensei-hacker wants to merge 38 commits intomaintenance-9.xfrom
feature/rp2350-port
Open

RP2350 (Pico 2) port — Milestone 1: Build system & empty target#45
sensei-hacker wants to merge 38 commits intomaintenance-9.xfrom
feature/rp2350-port

Conversation

@sensei-hacker
Copy link
Owner

@sensei-hacker sensei-hacker commented Feb 16, 2026

User description

Summary

Establish the CMake build system for RP2350 (Raspberry Pi Pico 2) so that make RP2350_PICO produces a linked ARM ELF binary. This is Milestone 1 of the RP2350 port — the binary uses stubs for all hardware interaction.

Changes

New platform files (9 files):

  • cmake/cortex-m33.cmake — Cortex-M33 CPU architecture flags
  • cmake/rp2350.cmake — Platform module with target_rp2350() function
  • src/main/target/RP2350_PICO/ — Board definition, system stubs, config
  • src/main/target/link/rp2350_flash.ld — Linker script (4MB flash, 512KB RAM)
  • src/main/startup/startup_rp2350.s — Minimal Cortex-M33 startup
  • src/main/startup/boot2_rp2350.S — 256-byte boot2 stage 2 stub

Modified existing files (14 files):

  • Added RP2350 guards alongside SITL_BUILD exclusions for hardware-specific code (EXTI, PWM, ADC, atomic, timer, IO, CLI, fc_init)
  • Added include(rp2350) to root CMakeLists.txt
  • Added RP2350 block to platform.h

Submodule:

  • Pico SDK 2.1.0 at lib/main/pico-sdk (headers only for M1)

Build Output

  • 694KB text, 9KB data, 95KB BSS
  • ARM ELF32, hard-float ABI, entry point in XIP flash region
  • .hex output generated

Test plan

  • make RP2350_PICO compiles and links successfully
  • Verify existing STM32/AT32/SITL targets unaffected (CI)
  • Future milestones: real hardware init, sensor drivers, motor output

PR Type

New Target


Description

This description is generated by an AI tool. It may have inaccuracies

  • Establish CMake build system for RP2350 (Pico 2) with Cortex-M33 support

  • Add platform configuration files: linker script, startup assembly, boot2 stub

  • Create RP2350_PICO target with hardware stubs for all drivers

  • Guard existing hardware-specific code paths with RP2350 exclusions

  • Integrate Pico SDK 2.1.0 as submodule for headers


Diagram Walkthrough

flowchart LR
  A["CMake Build System"] --> B["Cortex-M33 Config"]
  A --> C["RP2350 Platform Module"]
  C --> D["Linker Script"]
  C --> E["Startup Assembly"]
  C --> F["Boot2 Stage 2"]
  C --> G["Target Definition"]
  G --> H["Hardware Stubs"]
  H --> I["Drivers & System"]
  J["Pico SDK 2.1.0"] --> K["Headers Only"]
  L["Existing Code"] --> M["RP2350 Guards"]
  M --> N["EXTI, PWM, ADC, Timer, IO"]
  A --> O["Linked ARM ELF Binary"]
Loading

File Walkthrough

Relevant files
Configuration changes
5 files
cortex-m33.cmake
Cortex-M33 CPU architecture compiler flags                             
+23/-0   
rp2350.cmake
RP2350 platform CMake module with target function               
+181/-0 
rp2350_flash.ld
Linker script for 4MB flash and 512KB RAM layout                 
+190/-0 
CMakeLists.txt
CMake target invocation for RP2350_PICO build                       
+1/-0     
CMakeLists.txt
Include RP2350 CMake platform module                                         
+1/-0     
New feature
5 files
startup_rp2350.s
Minimal Cortex-M33 startup assembly with vector table       
+288/-0 
boot2_rp2350.S
256-byte boot2 stage 2 bootloader stub                                     
+29/-0   
target.h
Target board definitions and dummy type stubs                       
+163/-0 
target.c
Hardware stubs for system, timer, PWM, UART, DSP                 
+225/-0 
config.c
Target configuration function placeholder                               
+25/-0   
Enhancement
2 files
platform.h
Add RP2350 platform header block with U_ID                             
+7/-0     
config_streamer_ram.c
Add common/utils.h include for RP2350 support                       
+1/-0     
Bug fix
11 files
accgyro.c
Guard atomic.h include with RP2350 exclusion                         
+1/-1     
adc.c
Guard ADC driver implementation with RP2350 exclusion       
+1/-1     
exti.c
Guard EXTI driver with RP2350 exclusion                                   
+1/-1     
io.c
Add RP2350 case to IO_EXTI_Line function                                 
+1/-1     
io.h
Add RP2350 to IO configuration macro guards                           
+1/-1     
pwm_mapping.c
Guard PWM mapping with RP2350 exclusion                                   
+1/-1     
pwm_output.c
Guard PWM output driver with RP2350 exclusion                       
+1/-1     
timer.h
Add RP2350 timer type definitions and count                           
+7/-0     
timer_def.h
Add RP2350 case to timer definition includes                         
+1/-0     
cli.c
Guard CLI status output with RP2350 exclusion                       
+4/-4     
fc_init.c
Guard hardware initialization with RP2350 exclusion           
+6/-4     
Dependencies
2 files
.gitmodules
Add Pico SDK 2.1.0 as git submodule                                           
+3/-0     
pico-sdk
Pico SDK 2.1.0 submodule reference                                             
+1/-0     

Establish the CMake build system for RP2350 so that `make RP2350_PICO`
produces a linked .elf binary. The binary uses stubs for all hardware
interaction — this milestone is purely about build infrastructure.

New platform files:
- cmake/cortex-m33.cmake: Cortex-M33 CPU flags
- cmake/rp2350.cmake: Platform module with target_rp2350() function
- Linker script, startup assembly, boot2 stage 2 stub
- RP2350_PICO target: target.h (dummy types), target.c (system stubs),
  config.c, CMakeLists.txt

Existing files modified to add RP2350 guards alongside SITL_BUILD
exclusions for hardware-specific code paths (EXTI, PWM, ADC, atomic,
timer, IO config, CLI clock reporting, fc_init hardware init).

Pico SDK 2.1.0 added as submodule (headers only for M1).

Output: 694KB text, ARM ELF32 hard-float, entry in XIP flash region.
@qodo-code-review
Copy link

qodo-code-review bot commented Feb 16, 2026

PR Compliance Guide 🔍

Below is a summary of compliance checks for this PR:

Security Compliance
Non-unique device ID

Description: U_ID_0/U_ID_1/U_ID_2 are hardcoded to constant values for RP2350, which can break any code
that assumes these are per-device unique identifiers (e.g., deriving serial numbers, keys,
or binding tokens), potentially enabling device-impersonation or collisions if used for
authentication/anti-cloning features.
platform.h [81-87]

Referred Code
#elif defined(RP2350)
// RP2350 (Raspberry Pi Pico 2) - Cortex-M33
// Platform headers provided by target.h dummy types
#define U_ID_0 0
#define U_ID_1 1
#define U_ID_2 2
Ticket Compliance
🎫 No ticket provided
  • Create ticket/issue
Codebase Duplication Compliance
Codebase context is not defined

Follow the guide to enable codebase context checks.

Custom Compliance
🟢
Generic: Comprehensive Audit Trails

Objective: To create a detailed and reliable record of critical system actions for security analysis
and compliance.

Status: Passed

Learn more about managing compliance generic rules or creating your own custom rules

Generic: Meaningful Naming and Self-Documenting Code

Objective: Ensure all identifiers clearly express their purpose and intent, making code
self-documenting

Status: Passed

Learn more about managing compliance generic rules or creating your own custom rules

Generic: Robust Error Handling and Edge Case Management

Objective: Ensure comprehensive error handling that provides meaningful context and graceful
degradation

Status: Passed

Learn more about managing compliance generic rules or creating your own custom rules

Generic: Secure Error Handling

Objective: To prevent the leakage of sensitive system information through error messages while
providing sufficient detail for internal debugging.

Status: Passed

Learn more about managing compliance generic rules or creating your own custom rules

Generic: Secure Logging Practices

Objective: To ensure logs are useful for debugging and auditing without exposing sensitive
information like PII, PHI, or cardholder data.

Status: Passed

Learn more about managing compliance generic rules or creating your own custom rules

Generic: Security-First Input Validation and Data Handling

Objective: Ensure all data inputs are validated, sanitized, and handled securely to prevent
vulnerabilities

Status: Passed

Learn more about managing compliance generic rules or creating your own custom rules

  • Update
Compliance status legend 🟢 - Fully Compliant
🟡 - Partial Compliant
🔴 - Not Compliant
⚪ - Requires Further Human Verification
🏷️ - Compliance label

@qodo-code-review
Copy link

qodo-code-review bot commented Feb 16, 2026

PR Code Suggestions ✨

Explore these optional code suggestions:

CategorySuggestion                                                                                                                                    Impact
High-level
Re-evaluate the CMSIS-DSP stubbing strategy
Suggestion Impact:The commit removes the CMSIS-DSP stub implementations from src/main/target/RP2350_PICO/target.c and drops the arm_math.h include, aligning with the suggestion to stop stubbing CMSIS-DSP functions in target.c (though no corresponding CMake/ifdef strategy change is shown in this patch).

code diff:

-#include "arm_math.h"
+#include "drivers/serial_uart_impl.h"
 
-const int timerHardwareCount = 0;
-timerHardware_t timerHardware[1];
-uint32_t SystemCoreClock = 150000000; // 150 MHz RP2350
-
-// Called from startup_rp2350.s (uppercase)
-void SystemInit(void) { }
-
-void systemInit(void)
-{
-    // Stub - M1 does nothing
-}
-
-timeUs_t micros(void)
-{
-    return 0; // Stub
-}
-
-uint64_t microsISR(void)
-{
-    return 0; // Stub
-}
-
-uint32_t millis(void)
-{
-    return 0; // Stub
-}
-
-void delayMicroseconds(timeUs_t us)
-{
-    UNUSED(us);
-}
-
-void delay(timeMs_t ms)
-{
-    UNUSED(ms);
-}
-
-void systemReset(void)
-{
-    while (1) {}
-}
-
-void systemResetToBootloader(void)
-{
-    while (1) {}
-}
+/*
+ * Output mapping table — 8 GPIO pins in 4 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
+ *   GP16 = PB0   GP17 = PB1   GP18 = PB2   GP19 = PB3
+ */
+timerHardware_t timerHardware[] = {
+    /* slice 4 — motor group 1 */
+    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 2 */
+    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 8 — flexible group 1 */
+    DEF_TIM(TIM8, CH1, PB0,  TIM_USE_OUTPUT_AUTO, 0, 0),  /* GP16 */
+    DEF_TIM(TIM8, CH2, PB1,  TIM_USE_OUTPUT_AUTO, 0, 0),  /* GP17 */
+    /* slice 9 — flexible group 2 */
+    DEF_TIM(TIM9, CH1, PB2,  TIM_USE_OUTPUT_AUTO, 0, 0),  /* GP18 */
+    DEF_TIM(TIM9, CH2, PB3,  TIM_USE_OUTPUT_AUTO, 0, 0),  /* GP19 */
+};
+const int timerHardwareCount = 8;
 
 void failureMode(failureMode_e mode)
 {
@@ -91,136 +75,24 @@
     while (1) {}
 }
 
-uint32_t getEscUpdateFrequency(void)
-{
-    return 400;
-}
-
-pwmInitError_e getPwmInitError(void)
-{
-    return PWM_INIT_ERROR_NONE;
-}
-
-const char *getPwmInitErrorMessage(void)
-{
-    return "No error";
-}
-
-void IOConfigGPIO(IO_t io, ioConfig_t cfg)
-{
-    UNUSED(io);
-    UNUSED(cfg);
-}
-
-void timerInit(void)
-{
-    // NOP
-}
-
 bool isMPUSoftReset(void)
 {
     return false;
 }
 
-// PWM output stubs (pwm_output.c is guarded out for RP2350)
-void pwmWriteMotor(uint8_t index, uint16_t value)
-{
-    UNUSED(index);
-    UNUSED(value);
-}
-
-void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
-{
-    UNUSED(motorCount);
-}
-
-void pwmWriteServo(uint8_t index, uint16_t value)
-{
-    UNUSED(index);
-    UNUSED(value);
-}
-
-// Timer stub (timer.c is excluded from build)
-uint8_t timer2id(const HAL_Timer_t *tim)
-{
-    UNUSED(tim);
-    return 0;
-}
-
-// UART stub (no UART driver for RP2350 M1)
+// 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)
 {
-    UNUSED(USARTx);
-    UNUSED(rxCallback);
-    UNUSED(rxCallbackData);
-    UNUSED(baudRate);
-    UNUSED(mode);
-    UNUSED(options);
-    return NULL;
+    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;
 }
 
-// CMSIS DSP stubs (DSP library not compiled for RP2350 M1)
-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);
-}

Instead of stubbing CMSIS-DSP functions in target.c and using the ARM_MATH_CM4
flag as a workaround, consider a cleaner approach. Either update the CMSIS-DSP
library or use #ifdef directives to conditionally compile the code that relies
on these functions.

Examples:

src/main/target/RP2350_PICO/target.c [164-225]
// CMSIS DSP stubs (DSP library not compiled for RP2350 M1)
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)
{

 ... (clipped 52 lines)
cmake/cortex-m33.cmake [17-23]
set(CORTEX_M33_DEFINITIONS
    __FPU_PRESENT=1
    ARM_MATH_CM4
    ARM_MATH_MATRIX_CHECK
    ARM_MATH_ROUNDING
    UNALIGNED_SUPPORT_DISABLE
)

Solution Walkthrough:

Before:

// In cmake/cortex-m33.cmake
set(CORTEX_M33_DEFINITIONS
    ...
    ARM_MATH_CM4
    ...
)

// In src/main/target/RP2350_PICO/target.c
// CMSIS DSP stubs (DSP library not compiled for RP2350 M1)
arm_status arm_rfft_fast_init_f32(...) {
    // Stub implementation
    return ARM_MATH_SUCCESS;
}

void arm_cmplx_mag_f32(...) {
    // Stub implementation
}
// ... more stubs

After:

// In cmake/cortex-m33.cmake
set(CORTEX_M33_DEFINITIONS
    ...
    // ARM_MATH_CM4 is removed
    ...
)

// In src/main/target/RP2350_PICO/target.c
// The DSP stubs are removed.

// In common code (e.g. sensor processing)
#if defined(USE_CMSIS_DSP_FILTERS) // or similar new define
    // Existing code that calls CMSIS-DSP functions
    arm_rfft_fast_init_f32(...);
    arm_cmplx_mag_f32(...);
#endif
Suggestion importance[1-10]: 7

__

Why: The suggestion correctly identifies a temporary hack in the CMSIS-DSP integration for the new RP2350 target and proposes cleaner, more maintainable alternatives that improve the foundational quality of this new port.

Medium
Possible issue
Quote STREQUAL comparisons

Quote arguments in STREQUAL comparisons to prevent potential errors if variables
are empty.

cmake/rp2350.cmake [79-81]

-if(NOT arm-none-eabi STREQUAL TOOLCHAIN)
+if(NOT "arm-none-eabi" STREQUAL "${TOOLCHAIN}")
     return()
 endif()
 ...
-if (NOT generator_cmd STREQUAL "")
+if (NOT "${generator_cmd}" STREQUAL "")

[To ensure code accuracy, apply this suggestion manually]

Suggestion importance[1-10]: 5

__

Why: The suggestion correctly identifies a potential bug in the CMake script where an empty TOOLCHAIN variable would cause a syntax error, and provides a robust fix by quoting the arguments.

Low
  • Update

sensei-hacker and others added 26 commits February 17, 2026 01:27
Replace M1 stubs with real Pico SDK implementations:

System timing (system_rp2350.c):
- micros()/millis() via SDK hardware timer
- getCycleCounter() via Cortex-M33 DWT CYCCNT
- systemReset() via watchdog_reboot()
- systemResetToBootloader() via rom_reset_usb_boot()
- getUniqueId() via pico_get_unique_board_id()

GPIO abstraction (io_rp2350.c):
- Map GPIO 0-15 to Port A, GPIO 16-29 to Port B
- IORead/IOWrite/IOHi/IOLo/IOToggle via SDK gpio functions
- IOConfigGPIO guards against re-init of configured pins
- LED0 defined as PB9 (GPIO 25) for INAV LED driver

USB debug output:
- Integrate pico_stdio_usb with TinyUSB CDC
- printf("INAV RP2350 booting...") over USB serial
- Add ~45 Pico SDK and 7 TinyUSB source files to build

Build improvements:
- Add elf2uf2.py for UF2 generation from .bin
- Post-build generates .bin and .uf2 automatically
- Override C standard to C11 for Pico SDK compatibility
- Rewrite linker script for SDK crt0.S symbol requirements
Four bugs fixed, achieving Milestone 2 (LED @ 1Hz + USB CDC):

1. ram_vector_table 512-byte alignment
   Cortex-M33 VTOR clears the lower 9 bits of the written value, so the
   table must be aligned to the next power-of-2 >= table size.  RP2350
   has 68 exceptions × 4 = 272 bytes → 512-byte alignment required.
   Without it irq_set_exclusive_handler read wrong entries → hard-assert
   → panic → double fault.

2. .mutex_array embedded inside .data (> RAM AT> FLASH)
   SDK auto_init_mutex places mutex_t structs in .mutex_array; they must
   be copied to writable RAM at boot so mutex_init() can store the
   spin_lock pointer.  Two earlier attempts failed:
   - (NOLOAD) > RAM: KEEP(*.mutex_array.*) missed the bare .mutex_array
     section; spin_lock stayed garbage → BusFault PRECISERR at 0xa1279f3e
   - > FLASH only: XIP flash writes are silently discarded; spin_lock
     stayed NULL → infinite spin on ROM address 0x00000000
   Fix: add KEEP(*(.mutex_array)) alongside KEEP(*(SORT(.mutex_array.*)))
   inside the .data section so structs are loaded from flash into RAM.

3. Call tusb_init() before stdio_init_all()
   CFG_TUD_ENABLED=1 sets LIB_TINYUSB_DEVICE=1, which forces
   PICO_STDIO_USB_ENABLE_TINYUSB_INIT=0, so stdio_usb_init() skips
   tusb_init().  Must be called explicitly before stdio_init_all().

4. Add CFG_TUSB_RHPORT0_MODE to tusb_config.h
   Without this, TUD_OPT_RHPORT is undefined and tusb_init() skips
   tud_init(), leaving the USB hardware controller disabled.

Also add debug/openocd_helper.py — reusable SWD debug scripts for
PC sampling, fault analysis, and SWD flashing without BOOTSEL.

Co-Authored-By: Claude Sonnet 4.5 <noreply@anthropic.com>
GPS3DspeedFiltered was computed every PID cycle (1 kHz) from
gpsSol.velNED[], which only changes when the GPS task delivers a new
fix (~10 Hz). Move the sqrt and pt1 filter update into
imuCalculateTurnRateacceleration(), gate them on gpsHeartbeat change,
and make the filter state a static local. The variable is only
consumed in that function (fixed-wing + GPS-trustworthy path), so the
module-level FASTRAM variables and the imuInit() reset are also removed.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
pidController is FAST_CODE. Its callees that lacked FAST_CODE created
SRAM veneers (trampolines from ITCM to flash) on every call. Annotate
each callee that was audited as genuinely hot:

  pid.c:
    pTermProcess, dTermProcess, applyItermLimiting,
    pidApplySetpointRateLimiting, checkItermLimitingActive,
    checkItermFreezingActive, pidRcCommandToAngle, pidRcCommandToRate

  smith_predictor.c: applySmithPredictor

  filter.c: pt1ComputeRC (static; called from FAST_CODE pt1FilterApply4)

  maths.c: constrain, constrainf, scaleRangef
    (called from the pid.c functions above; candidates for static inline
    in a future refactor, but FAST_CODE resolves the veneer for now)

  fc_core.c: getAxisRcCommand

Functions removed from FAST_CODE where no FAST_CODE caller existed
(sin_approx, cos_approx, fast_fsqrtf, failsafeShouldApplyControlInput)
were never added in this tree; no net change for those.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Two independent optimisations for the main PID loop:

rcCommand caching (fc_core.c)
  getAxisRcCommand() and failsafeUpdateRcCommandValues() are now gated
  on isRXDataNew so they only run when the RX task delivers a fresh
  frame (~50 Hz) instead of every PID cycle (1 kHz / multirotor rate).
  rcCommand[] is updated from a small cache on every cycle so the rest
  of the code is unaffected.

pidSumLimit precomputation (pid.c)
  getPidSumLimit() returns 400 or 500 based on vehicle type and axis —
  values that are constant for the lifetime of a flight. Add a
  pidSumLimit field to pidState_t, initialise it once in pidInit(), and
  replace the two hot-path calls in pidApplyFixedWingRateController and
  pidApplyMulticopterRateController with a struct field read.
  getPidSumLimit() is retained for pid_autotune.c (not hot).

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
USB VCP (target.h, cmake, drivers/)
  Enable USE_VCP, set SERIAL_PORT_COUNT 3 (VCP + UART1 + UART2), add
  serial_usb_vcp_rp2350.c to the build.  Drive tud_task() from a 1 ms
  repeating hardware timer so USB remains responsive regardless of
  scheduler state (same approach pico_stdio_usb uses internally).

FAST_CODE → SRAM (target.h, rp2350_flash.ld)
  Redefine FAST_CODE as __attribute__((section(".time_critical.inav")))
  so annotated functions are copied to SRAM at boot and avoid XIP cache
  pressure on the hot PID/gyro path.  Remove *(.time_critical*) from
  the .text (flash) section so those symbols land in .data (RAM AT>
  FLASH) as intended.

Scheduler rates (fc_tasks.c)
  Reschedule GYRO and PID to 1000 µs on RP2350.  The default 250 µs
  causes task starvation when gyro occasionally overruns its period;
  1000 µs gives comfortable headroom on this target.

Default config (config.c)
  Disable dynamic notch filter by default: the board is
  performance-constrained and wing aircraft do not require it.
Five cycle-saving changes to imuMahonyAHRSupdate(), which accounts for
~205 µs (30%) of the PID loop on RP2350.  Each change is safe on all
targets; the gains are proportionally smaller on F7/H7 where the function
already lives in ITCM RAM.

1. Replace quaternionRotateVector({0,0,1}) with rMat[2][*] reads.
   imuComputeRotationMatrix() is called at the end of every invocation and
   keeps rMat in sync with orientation.  Rotating the constant gravity
   vector EF→BF yields exactly the third row of rMat, so three float loads
   replace ~56 floating-point multiply/add operations.

2. Eliminate sqrt() from the Taylor-series threshold.
   Original: thetaMagnitudeSq < sqrt(24e-6).
   Squaring both sides (both non-negative) gives the equivalent condition
   thetaMagnitudeSq² < 24e-6 with no sqrt call.

3. First-order Newton quaternion renormalization replaces quaternionNormalize()
   (sqrt + 4 divides, ~35 cycles) with scale = (3 - normSq) * 0.5 (~14 cycles).
   At 1 kHz the per-step drift |ε| < 1e-6, making the O(ε²) error < 1e-12.
   imuCheckAndResetOrientationQuaternion() remains as the catastrophic-failure
   safety net.

4. Precompute the anti-windup i_limit in imuConfigure() (called only on
   settings save).  The hot path now reads a single float instead of
   performing an add, a multiply, and a divide every PID cycle.
   Adds dcm_i_limit to imuRuntimeConfig_t and imuConfigure().

5. Reduce prevOrientation snapshot frequency from every PID cycle to
   every 100 cycles (~100 ms at 1 kHz).  The snapshot is only used by
   the fault-recovery path which should never fire in normal flight;
   16 bytes of unnecessary SRAM write every ms is not justified.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Introduces a new RP2350_FAST_CODE attribute for functions too large to fit
in F7 ITCM (budget ~5 KB free) but that are dominant XIP-cache hotspots on
RP2350.  On RP2350 it maps to FAST_CODE (.time_critical.inav → .data > RAM);
on all other targets it is a no-op.

Functions moved to SRAM:
  imuMahonyAHRSupdate       ~2 KB — Mahony quaternion integrator, 205 µs
  imuUpdateEulerAngles              — atan2×2 + acos×1, 62 µs
  imuCalculateEstimatedAttitude     — wrapper calling both of the above
  imuComputeRotationMatrix          — called at end of every Mahony update
  atan2_approx / acos_approx        — callee chain for imuUpdateEulerAngles;
                                      without this, every call from SRAM
                                      incurs a SRAM→flash veneer + XIP miss

Measured result on RP2350 at 1 kHz:
  PID avg before:  710 µs (avgload 69%)
  PID avg after:   575 µs (avgload 53%)
  Improvement:    -135 µs / 19%

F7 ITCM is unchanged: RP2350_FAST_CODE is a no-op there.
processPilotAndFailSafeActions, throttleStickMixedValue, and
rcLookupThrottle all run on every 1 kHz PID cycle from QSPI flash.
Moving them to SRAM eliminates the XIP cache-miss penalty on each
function entry.

applyRateDynamics (×3/cycle) and getAxisRcCommand were already FAST_CODE;
these three complete the per-cycle call chain.

Measured on RP2350_PICO: PID avg 575 µs → 546 µs (-29 µs, -5%).
updatePositionEstimator and its per-cycle callees all run from QSPI flash
at 1 kHz. Drill-down profiling identified updateIMUTopic as dominant
(~65 µs) followed by updateEstimatedTopic (~20 µs).

Move to SRAM (RP2350_FAST_CODE):
  - updatePositionEstimator          (76 B, wrapper)
  - updateIMUEstimationWeight       (236 B, callee of updateIMUTopic)
  - updateIMUTopic                  (692 B, dominant cost)
  - updateEstimatedTopic           (1324 B, second-largest nav cost)
  - imuTransformVectorBodyToEarth    (48 B, called every cycle from updateIMUTopic)

publishEstimatedTopic (992 B) is excluded: its body is timer-gated at
~50 Hz so XIP pressure from it is negligible at 1 kHz.

Total new SRAM: ~2.4 KB. RAM usage: 126 KB → 129 KB (512 KB available).

Measured on RP2350_PICO: PID avg 546 µs → 503 µs (-43 µs, -8%).
Cumulative from original 710 µs baseline: -207 µs (-29%).
The RP2350 is rated for 200+ MHz at default voltage. Raising from the
pico-sdk default (150 MHz) to 192 MHz gives a 28% raw throughput
increase on SRAM-resident code and proportionally reduces all task
execution times.

set_sys_clock_khz(192000, true) is called at the start of systemInit(),
before tusb_init() and stdio_init_all(). The USB PLL (clk_usb, 48 MHz
from pll_usb) is independent of sys PLL, so TinyUSB CDC is unaffected.
The hardware timer (clk_timer from clk_ref at 12 MHz) is also
independent, so micros() accuracy is preserved.

Measured on RP2350_PICO: PID avg 503 µs → 360 µs (-143 µs, -28%).
Cumulative from the 710 µs baseline: 360 µs (-350 µs, -49%).
Remove the #ifdef RP2350 block in fcTasksInit() that hard-coded GYRO
and PID task periods to 1000 µs. That block was added because the GYRO
task (then ~343 µs max) exceeded its default 250 µs period, causing
scheduler starvation.

With FAST_CODE and 192 MHz, GYRO now averages 18 µs (max 80 µs), well
within any reasonable period. Both tasks can use the standard
getLooptime() / getGyroLooptime() path.

PID still needs 1 kHz: the default looptime is 500 µs but PID averages
~390 µs with occasional peaks near 833 µs, leaving insufficient
headroom for GPS/nav at 2 kHz. Set looptime = 1000 in
targetConfiguration() — the proper INAV pattern for target-specific
rate configuration.

Result: PID 993 Hz (39% avg load), GYRO 1088 Hz at natural rate,
total system load 47% avg — identical to the #ifdef approach but
without the non-standard override.
- serial_usb_vcp_rp2350.c: remove blocking spin-loop from usbVcpRead();
  callers must check serialRxBytesWaiting() > 0 first (INAV contract)
- system_rp2350.c: remove debugBlink() causing 1.5 s boot delay; gate
  diagnostic blink hooks behind #ifdef RP2350_DIAG_BLINK
- system_rp2350.c: check add_repeating_timer_ms() return value
- system_rp2350.c: replace two-loop getUniqueId() with memcpy + memset
- io_rp2350.c: IO_GPIOPortIdx() now returns IO_Pin(io) >> 4 so GPIO 16+
  correctly reports port index 1 (port B)
- imu.c: reduce prevOrientation snapshot interval from 100 to 10 cycles
  (100 ms → 10 ms staleness for the fault-recovery quaternion reset path)
- tusb_config.h: add TinyUSB version note to OPT_MCU_RP2040 comment
acceleration.c / .h: track maxGSq instead of maxG so updateAccExtremes()
(called every PID cycle) uses sq(x)+sq(y)+sq(z) comparison instead of
calc_length_pythagorean_3D. accGetMeasuredMaxG() now calls fast_fsqrtf()
only when OSD/MSP requests the value (rare path).

wind_estimator.c: replace two calc_length_pythagorean_3D calls with
squared-norm arithmetic. The sanity check becomes:
  windSq < sq(fast_fsqrtf(prevWindSq) + 4000)
which is mathematically equivalent to the original
  windLength < prevWindLength + 4000
but eliminates one sqrt entirely.
Adds full serial port support for RP2350_PICO:

  UART1 (INAV) → RP2350 uart0, GP0/1  — hardware PL011, IRQ-driven
  UART2 (INAV) → RP2350 uart1, GP2/3  — hardware PL011, IRQ-driven
  UART3 (INAV) → PIO1 SM0+SM1, GP12/13 — PIO soft-UART
  UART4 (INAV) → PIO1 SM2+SM3, GP14/15 — PIO soft-UART

New files:
  drivers/serial_uart_rp2350.c  — HW UART driver with gpio inversion for SBUS
  drivers/uart_pio_rp2350.c     — PIO UART driver, pre-assembled TX/RX programs

All four ports tested via serialpassthrough loopback on hardware (Pico 2 +
debugprobe). 0x00/0xFF/alternating-bit byte patterns pass. PIO2 SM0 reserved
for future WS2812 LED strip.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Critical:
- Move piouartInit() outside #ifdef USE_UART3 guard; it is called by
  serialUART4 so it must compile whenever USE_UART3 || USE_UART4 is defined.
  Add explanatory comment above the function.

Important:
- PIO UARTs: pass options through piouartInit(); apply SERIAL_INVERTED via
  gpio_set_inover/outover at open time and in pioUartSetOptions().
  Previously options were discarded (UNUSED), silently breaking SBUS on UART3/4.
- HW UARTs: remove spurious (uint8_t *) cast on volatile uint8_t[] buffer
  assignments; the implicit conversion is correct and avoids -Wall warning.
- PIO UARTs: same volatile-cast fix in piouartInit().
- Add comment to pioUartSetBaudRate() noting hardware FIFO bytes are discarded
  on baud-rate change; callers doing GPS auto-baud should drain first.

Minor:
- uartOpen(): use else-if chain instead of four independent if statements.
- HW UARTs: guard gpio_set_function(tx_pin) behind (mode & MODE_TX) and
  gpio_set_function(rx_pin) behind (mode & MODE_RX) to avoid asserting UART
  function on pins that should stay high-impedance (e.g. RX-only SBUS port).
- target.h: remove redundant inline remark about GP4/5 in UART2 comment block.
gpio_set_outover(tx_pin, GPIO_OVERRIDE_NORMAL) called after
uart_tx_program_init / pio_gpio_init caused the PIO TX to stop
transmitting. pio_gpio_init already leaves the GPIO in normal
(non-overridden) state, so explicitly setting OUTOVER=NORMAL
was redundant and apparently problematic.

Fix: only call gpio_set_inover/outover when SERIAL_INVERTED is
actually requested. Leave GPIO state untouched otherwise.

pioUartSetOptions retains the else branch because it may need
to clear a previously set inversion when options change at runtime.

Tested: UART3 loopback (GP12-GP13 wired) passes 6/6 byte patterns
including 0x00, 0xFF, 0x55, 0xAA, ASCII, and 64-byte ramp.
Implements INAV's motor output API for the RP2350 using DShot 600
over PIO0.  One state machine per motor (up to 4); all SMs are
stopped, their TX FIFOs loaded, then restarted together via
pio_enable_sm_mask_in_sync() so every frame begins on the same
system-clock edge.

The PIO program is pre-assembled (instruction array embedded in C),
matching the approach used by uart_pio_rp2350.c — no pioasm build
step required.

Motor pin assignments (target.h):
  M1 → GP8  (PIO0 SM0)
  M2 → GP9  (PIO0 SM1)
  M3 → GP10 (PIO0 SM2)
  M4 → GP11 (PIO0 SM3)

Changes:
- drivers/pwm_output_rp2350.c: new file — DShot 600 PIO driver;
  provides all motor output API functions (pwmWriteMotor,
  pwmCompleteMotorUpdate, pwmMotorAndServoInit, etc.)
- target.h: add USE_DSHOT, MOTOR1_PIN..MOTOR4_PIN (GP8-11)
- target.c: remove motor/ESC stubs superseded by new driver
- cmake/rp2350.cmake: add pwm_output_rp2350.c to RP2350_SRC
- fc_init.c: remove RP2350 from motor init exclusion guard so
  pwmMotorAndServoInit() is called on RP2350

Build: FLASH 794 KB / 4 MB (19%), RAM 132 KB / 512 KB (25%).
Address review feedback on pwm_output_rp2350.c:

- Add re-initialization guard at top of pwmMotorAndServoInit() to
  prevent PIO instruction memory and SM leaks on repeated calls
- Drain TX FIFO before pio_sm_put() to discard any stale packet
  from a missed scheduler cycle
- Fix GPIO base comment: RP2350 PIO uses a 32-pin window (not 16)
- Fix clkdiv comment: formula was missing the /1e6 factor
- Fix PIO header comment: replace stale "at 150 MHz" with current
  192 MHz (clkdiv = 8.0) note
- Drop redundant (uint8_t) cast on dshotMotorCount comparison
Replace the RAM-only config stub (CONFIG_IN_RAM + config_streamer_ram.c)
with real flash-backed persistent storage using the Pico SDK flash APIs.

Settings are stored in the FLASH_CONFIG linker region (0x103F0000, 64 KB)
defined in rp2350_flash.ld.  The region is XIP-mapped so reads happen
transparently as normal memory accesses.  Writes use:
  flash_range_erase()   — 4 KB sector granularity
  flash_range_program() — 256-byte page granularity

The config_streamer interface delivers 4 bytes per write_word() call.
config_streamer_rp2350.c accumulates words into a 256-byte page buffer
and programs each full page to flash.  config_streamer_impl_lock()
flushes any partial final page (padded with 0xFF) before finishing.
Interrupts are disabled for the duration of each flash operation.

Changes:
- config/config_streamer_rp2350.c: new file — RP2350 flash streamer
- target.h: CONFIG_IN_RAM → CONFIG_IN_FLASH
- cmake/rp2350.cmake: config_streamer_ram.c → config_streamer_rp2350.c

Side-effect: RAM usage drops 32 KB (eepromData[] buffer eliminated).
Build: FLASH 795 KB / 4 MB (19%), RAM 100 KB / 512 KB (19%).

Note: multicore flash safety (flash_safe_execute) deferred to M12.
- Use SDK macros XIP_BASE, FLASH_PAGE_SIZE, FLASH_SECTOR_SIZE instead
  of private redefinitions that could silently disagree with the SDK
- Change guard to #if defined(RP2350) && defined(CONFIG_IN_FLASH) to
  match the pattern every other platform streamer uses; prevents the
  flash-erasing code running if CONFIG_IN_RAM is ever used on RP2350
- Have write_word() call flushPageBuffer() for the full-page case
  instead of duplicating the program-and-advance logic inline
- Add offsetInPage bounds check in write_word() to guard against
  caller bugs or unexpected c->address rewinds
- Cast address arithmetic through uintptr_t before uint32_t to be
  explicit about pointer-to-integer conversion
- Replace non-ASCII box-drawing comment separators with plain ASCII
- Add WHY comment explaining the eager-erase strategy in unlock()
…array

Motor GPIO numbers do not belong as #define macros in target.h — no other
INAV target uses that pattern.  The standard convention is for motor output
routing data to live in target.c (analogous to timerHardware[] on STM32).

- target.h: remove MOTOR1_PIN..MOTOR4_PIN defines; keep USE_DSHOT
- target.c: add rp2350MotorPins[] and rp2350MotorPinCount as target data
- pwm_output_rp2350.c: reference pins via extern instead of #defines;
  also guard against motorCount exceeding rp2350MotorPinCount
The PIO clock divider was hardcoded for DShot 600 (1.667 µs bit period)
regardless of which protocol was selected.  DShot 150 and 300 were
therefore running 4× and 2× too fast respectively.

Fix: derive bitPeriodUs from initProtocol before calculating clkdiv.
The PIO program cycle counts (DSHOT_BIT_PERIOD = 40) are unchanged;
only the time-per-cycle differs between speeds.

Expected clkdiv @ 192 MHz:
  DShot 150: 32.0  (6.667 µs / 40 cycles)
  DShot 300: 16.0  (3.333 µs / 40 cycles)
  DShot 600:  8.0  (1.667 µs / 40 cycles)
Servo PWM (hardware PWM slices, 50 Hz, GP16-GP19):
- pwm_output_rp2350.c: init 4 servo outputs via hardware PWM slices.
  Adjacent pins share a slice (GP16/17, GP18/19); track initialized
  slices with a bitmask to avoid re-init clobbering the partner channel.

Standard PWM motors (hardware PWM slices, 400 Hz, GP8-GP11):
- Non-DShot protocols now use hardware PWM on the motor GPIO pins.
  Same shared-slice guard as servos (GP8/9 share slice 4, GP10/11
  share slice 5).  Falls through to servo init via goto servo_init,
  so fixed-wing configs get servos regardless of motor protocol.

ADC (DMA ring buffer, GP26-GP28, ~10 samp/sec):
- adc_rp2350.c: new driver implementing the full INAV ADC API.
  Samples ADC0-ADC3 (GPIO26-29) in round-robin; pads 3 real channels
  to 4 for power-of-2 DMA ring sizing.  Bug fixes from code review:
  · Add adc_fifo_setup() so DREQ_ADC is asserted (DMA was stalling)
  · Read from adc_hw->fifo (not adc_hw->result) for DMA pacing
  · Declare adcDmaBuf volatile + 8-byte aligned for DMA ring mode
  · Use dma_claim_unused_channel(false) and check for failure
- adc.c: guard generic stub functions behind #if !defined(RP2350)
  to avoid duplicate symbols with the real RP2350 driver.
- cmake/rp2350.cmake: add adc_rp2350.c, hardware_adc, hardware_dma.
- target.h: add VBAT/CURRENT/RSSI ADC channel defaults; servo pin
  externs; remove redundant extern re-declarations from .c bodies.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
- timerHardware[]: populated with 8 entries across 4 PWM slice groups
  using DEF_TIM() macro syntax matching other INAV targets; slice groups
  exposed as TIM4/TIM5/TIM8/TIM9 pointer macros (slice = gpio/2)
- HARDWARE_TIMER_DEFINITION_COUNT: 0 → 4, enabling timerOverrides[] PG
  array and Configurator output-group control
- pwmMotorAndServoInit(): rewritten to iterate timerHardware[] and read
  timerOverrides(sliceId)->outputMode instead of fixed pin arrays
- UART1–4 pin defines: raw GPIO integers → PA/PB port notation
  (PA0–PA3, PA12–PA15) matching INAV conventions on all other targets;
  drivers convert back to GPIO number via ioTagToGpioNum(IO_TAG(pin))
- uartGetPortPins(): returns real ioTags for UART1–4 instead of NONE;
  file guard extended to compile whenever any UART is defined
- timer_def.h: DEF_TIM macro added for RP2350 (6-param, flags/dma unused)
- dshotProgram struct: added pio_version/used_gpio_ranges fields to match
  UART PIO program structs in the same file tree
system_rp2350.c (timing, reset, USB init, CMSIS DSP stubs) moves from
target/RP2350_PICO/ to drivers/, analogous to system_stm32f7xx.c.

timer_rp2350.c (rp2350Pwm4/5/8/9 identity tokens, timerInit, timer2id)
is new in drivers/; these are determined by the RP2350 chip (slice =
gpio/2), not by any board pinout.

target.c retains only board-specific content: timerHardware[], uartOpen(),
failureMode(), isMPUSoftReset().  cmake/rp2350.cmake updated to compile
both new driver files and corrects a stale comment.
Remove #include "target.h" (processor code should not depend on board pin
definitions), update file header to reflect new location in drivers/, and
move CMSIS DSP stubs here from target.c.  The stubs were always processor-
level; they are now alongside the rest of the processor initialisation code.
After assigning each PWM slice as motor or servo, update the
corresponding timerHardware[].usageFlags entries from TIM_USE_OUTPUT_AUTO
to TIM_USE_MOTOR or TIM_USE_SERVO.

MSP2_INAV_OUTPUT_MAPPING_EXT2 reads usageFlags directly, so the
configurator was seeing AUTO for all outputs and applying its servo-first
assignment order, placing servos on Timer 1 and motors on Timer 2.
STM32's pwm_mapping.c performs the same resolution step before MSP reads
the mapping. With this fix the configurator correctly shows motors on the
first timers and servos following.
Add FEATURE_VBAT to DEFAULT_FEATURES so battery voltage monitoring
is active out of the box on fresh EEPROM. Previously only FEATURE_GPS
was enabled by default, requiring users to manually enable VBAT.

GPIO26 (ADC_CHN_1) is the hardware-fixed VBAT ADC input on RP2350A.
GP16-19 are reserved on the RP2350_PICO (Option C) board layout:
  GP16 = SPI flash CS
  GP17 = Beeper
  GP18 = I2C1 SDA (baro/mag)
  GP19 = I2C1 SCL

Move servo outputs to GP20/GP21 (PWM slice 10), which are free.
Reduce HARDWARE_TIMER_DEFINITION_COUNT from 4 to 3 to match the
three slice groups now in use (slice 4, slice 5, slice 10).

timerHardware[] now has 6 entries in 3 groups:
  TIM4  / slice 4:  GP8,  GP9  — motors 1-2 (DShot)
  TIM5  / slice 5:  GP10, GP11 — motors 3-4 (DShot)
  TIM10 / slice 10: GP20, GP21 — servos (50 Hz PWM)

Verified via SWD: servoHwPins=[20,21], servoCount=2, dshotMotorCount=4.
Add PWM slice 6 (GP12/GP13) and slice 7 (GP14/GP15) to timerHardware[].
These pins are dual-use with UART3 and UART4 (PIO1 software serial) —
when a UART is assigned in the Configurator ports tab the pins act as
serial; when unassigned they are available as servo outputs.

HARDWARE_TIMER_DEFINITION_COUNT: 3 → 5 (slices 4, 5, 6, 7, 10)
timerHardwareCount: 6 → 10

Output groups now visible in Configurator:
  TIM4  / slice 4:  GP8,  GP9  — motors 1-2 (DShot)
  TIM5  / slice 5:  GP10, GP11 — motors 3-4 (DShot)
  TIM6  / slice 6:  GP12, GP13 — SERVO3/4 (dual-use UART3)
  TIM7  / slice 7:  GP14, GP15 — SERVO5/6 (dual-use UART4)
  TIM10 / slice 10: GP20, GP21 — SERVO1/2 (dedicated)

Verified via SWD: servoHwPins=[12,13,14,15,20,21], servoCount=6.
Implement USE_LED_STRIP for RP2350 using PIO2 (block 2) and a
DMA channel, replacing the STM32 timer/DMA abstraction that the
generic light_ws2811strip.c requires.

Changes:
- cmake/rp2350.cmake: exclude generic light_ws2811strip.c from
  COMMON_SRC; add light_ws2811strip_rp2350.c to RP2350_SRC
- target.h: enable USE_LED_STRIP; define WS2811_PIN=PB6 (GP22)
  and PIO_LEDSTRIP_INDEX=2 (PIO2 SM0)
- light_ws2811strip_rp2350.c: new RP2350-specific implementation
  - 4-instruction WS2812 PIO program (T1=3, T2=3, T3=4 @ 800 kHz)
  - DMA streams GRB words from led_data[] to PIO TX FIFO; polled
    for completion via dma_channel_is_busy() — no IRQ needed
  - provides all functions from light_ws2811strip.h including the
    PG registration, color buffer helpers, and ledPin stubs

GP22 is free from flash CS, beeper, I2C1, SPI, and all UARTs.
Add blocking SPI and I2C drivers for RP2350 using the Pico SDK,
and move chip-level type stubs from target.h into a dedicated
rp2350.h chip header, matching the pattern used by STM32 targets
(platform.h includes stm32f7xx.h etc.).

Platform type stubs:
- New src/main/rp2350.h: TIM_TypeDef, SPI_TypeDef, USART_TypeDef,
  GPIO_TypeDef, IRQ/EXTI enums, USART1-8/UART4/5/7/8 pointer
  constants, SystemCoreClock extern
- platform.h: RP2350 block now does #include "rp2350.h" instead of
  inlining definitions; target.h now contains only board-specific
  content (pin assignments, feature enables, timer externs)

SPI driver (bus_spi_rp2350.c):
- Implements full bus_spi.h interface via Pico SDK hardware_spi
- GPIO-to-hardware mapping: ((sck_gpio >> 3) & 1) ? spi1 : spi0
- MISO pull-up on init to prevent floating on shared bus
- Fast slew rate on SCK at high data rates
- Speed table: 328 kHz init → 1/10/20/40 MHz
- bus_spi.h: add RP2350 SPI_IO_CS_CFG (bit 0=output, bits 5-6 clear)

I2C driver (bus_i2c_rp2350.c):
- Implements full bus_i2c.h interface via Pico SDK hardware_i2c
- Maps I2CDEV_1 → i2c1 on GP18/GP19 (PB2/PB3)
- On-chip pull-ups enabled; external resistors dominate if fitted
- allowRawAccess support for drivers that skip the register byte

target.h additions:
- DEFAULT_I2C_BUS / MAG_I2C_BUS / BARO_I2C_BUS = BUS_I2C1
- USE_BARO + USE_BARO_ALL (real barometer drivers)
- USE_MAG + USE_MAG_ALL (real magnetometer drivers)
- USE_SPI / USE_SPI_DEVICE_1 with GP4/6/7 pin assignments
- USE_I2C / USE_I2C_DEVICE_1 with GP18/GP19 pin assignments

system_rp2350.c:
- Add delayNanos() using busy_wait_us_32 (rounds up to µs)
  with signed-overflow guard (cast to uint32_t before addition)

cmake/rp2350.cmake:
- Exclude bus_spi_hal_ll.c and bus_i2c_hal.c (STM32 HAL only)
- Add bus_spi_rp2350.c, bus_i2c_rp2350.c to RP2350_SRC
- Add hardware_spi/spi.c, hardware_i2c/i2c.c to PICO_SDK_SOURCES
Add persistent_rp2350.c using watchdog scratch registers, which survive
a watchdog-triggered reboot but are cleared on power-on reset — the
direct equivalent of STM32 RTC backup registers.  Call persistentObjectInit()
from systemInit() before any code that reads or writes a reset reason.

Remove comments across RP2350 driver files that only restate what the
immediately following line of code already says clearly.  Retain comments
that explain non-obvious behaviour, cryptic register/API names, or the
reason a particular approach was chosen over the obvious alternative.
Remove the !defined(RP2350) guard from the RESET_NONE write in fc_init.c
now that persistent_rp2350.c is implemented.  Without this, the reset
reason scratch register was never cleared after a normal boot.

Add systemResetRequest() to system_rp2350.c to match the declaration in
system.h (system.c is excluded from the RP2350 build).  Writes the reason
to the watchdog scratch register before triggering a watchdog reboot, so
the reason survives the reset and can be consumed on the next boot.

Tested on hardware: 3 consecutive save/reboot cycles all succeeded with
sub-1-second reconnect time and clean version checks.  DFU mode entry
via the dfu CLI command also confirmed working.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant