This is an automated email from the ASF dual-hosted git repository.

xiaoxiang pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/nuttx.git


The following commit(s) were added to refs/heads/master by this push:
     new 14000d077d seeed-xiao-rp2040: Add initial board support
14000d077d is described below

commit 14000d077d77102014fe0d461ffe500e3730c23f
Author: Rodrigo Sim <rcsi...@gmail.com>
AuthorDate: Sun Nov 26 22:48:48 2023 -0300

    seeed-xiao-rp2040: Add initial board support
---
 .../arm/rp2040/boards/seeed-xiao-rp2040/README.txt |  96 +++++
 .../arm/rp2040/boards/seeed-xiao-rp2040/index.rst  |  98 ++++++
 .../boards/seeed-xiao-rp2040/seeed-xiao-rp2040.jpg | Bin 0 -> 64755 bytes
 LICENSE                                            |  36 ++
 boards/Kconfig                                     |  11 +
 boards/arm/rp2040/seeed-xiao-rp2040/Kconfig        |   8 +
 .../rp2040/seeed-xiao-rp2040/configs/nsh/defconfig |  47 +++
 .../arm/rp2040/seeed-xiao-rp2040/include/board.h   | 116 ++++++
 .../seeed-xiao-rp2040/include/rp2040_i2cdev.h      |  72 ++++
 .../seeed-xiao-rp2040/include/rp2040_i2sdev.h      |  72 ++++
 .../seeed-xiao-rp2040/include/rp2040_spidev.h      |  69 ++++
 .../seeed-xiao-rp2040/include/rp2040_spisd.h       |  83 +++++
 .../arm/rp2040/seeed-xiao-rp2040/scripts/Make.defs |  45 +++
 .../scripts/seeed-xiao-rp2040-flash.ld             | 119 +++++++
 .../scripts/seeed-xiao-rp2040-sram.ld              | 105 ++++++
 boards/arm/rp2040/seeed-xiao-rp2040/src/Make.defs  |  33 ++
 .../rp2040/seeed-xiao-rp2040/src/rp2040_appinit.c  |  76 ++++
 .../seeed-xiao-rp2040/src/rp2040_boardinitialize.c |  87 +++++
 .../rp2040/seeed-xiao-rp2040/src/rp2040_bringup.c  |  63 ++++
 .../arm/rp2040/seeed-xiao-rp2040/src/rp2040_gpio.c | 392 +++++++++++++++++++++
 .../arm/rp2040/seeed-xiao-rp2040/src/rp2040_pico.h |  36 ++
 21 files changed, 1664 insertions(+)

diff --git 
a/Documentation/platforms/arm/rp2040/boards/seeed-xiao-rp2040/README.txt 
b/Documentation/platforms/arm/rp2040/boards/seeed-xiao-rp2040/README.txt
new file mode 100644
index 0000000000..c48969f346
--- /dev/null
+++ b/Documentation/platforms/arm/rp2040/boards/seeed-xiao-rp2040/README.txt
@@ -0,0 +1,96 @@
+README
+======
+
+This directory contains the port of NuttX to the Seeed Studio Xiao RP2040.
+See https://wiki.seeedstudio.com/XIAO-RP2040/ for information about Seeed
+Studio Xiao RP2040.
+
+NuttX supports the following RP2040 capabilities:
+  - UART  (console port)
+    - GPIO 0 (UART0 TX) and GPIO 1 (UART0 RX) are used for the console.
+  - I2C
+  - SPI (master only)
+  - DMAC
+  - PWM
+  - ADC
+  - Watchdog
+  - USB device
+    - MSC, CDC/ACM serial and these composite device are supported.
+    - CDC/ACM serial device can be used for the console.
+  - PIO (RP2040 Programmable I/O)
+  - Flash ROM Boot
+  - SRAM Boot
+    - If Pico SDK is available, nuttx.uf2 file which can be used in
+      BOOTSEL mode will be created.
+  - Persistent flash filesystem in unused flash ROM
+
+NuttX also provides support for these external devices:
+
+  - BMP180 sensor at I2C0 (don't forget to define I2C0 GPIOs at "I2C0 GPIO pin 
assign" in Board Selection menu)
+  - INA219 sensor / module (don't forget to define I2C0 GPIOs at "I2C0 GPIO 
pin assign" in Board Selection menu)
+  - WS2812 smart pixel support
+
+There is currently no direct user mode access to these RP2040 hardware 
features:
+  - SPI Slave Mode
+  - SSI
+  - RTC
+  - Timers
+
+Installation
+============
+
+1. Download Raspberry Pi Pico SDK and update submodule(cyw43-driver)
+
+  $ git clone -b 1.4.0 https://github.com/raspberrypi/pico-sdk.git
+  $ cd pico-sdk
+  $ git submodule update --init --recursive lib/cyw43-driver
+
+2. Set PICO_SDK_PATH environment variable
+
+  $ export PICO_SDK_PATH=<absolute_path_to_pico-sdk_directory>
+
+3. Configure and build NuttX
+
+  $ git clone https://github.com/apache/nuttx.git nuttx
+  $ git clone https://github.com/apache/nuttx-apps.git apps
+  $ cd nuttx
+  $ make distclean
+  $ ./tools/configure.sh seeed-xiao-rp2040:nsh
+  $ make V=1
+
+4. Connect Seeed Studio Xiao RP2040 board to USB port while pressing BOOTSEL.
+   The board will be detected as USB Mass Storage Device.
+   Then copy "nuttx.uf2" into the device.
+   (Same manner as the standard Pico SDK applications installation.)
+
+5. To access the console, GPIO 0 and 1 pins must be connected to the
+   device such as USB-serial converter.
+
+   `usbnsh` configuration provides the console access by USB CDC/ACM serial
+   devcice.  The console is available by using a terminal software on the USB
+   host.
+
+Defconfigs
+==========
+
+- nsh
+    Minimum configuration with NuttShell
+
+License exceptions
+==================
+
+The following files are originated from the files in Pico SDK.
+So, the files are licensed under 3-Clause BSD same as Pico SDK.
+
+- arch/arm/src/rp2040/rp2040_clock.c
+- arch/arm/src/rp2040/rp2040_pll.c
+- arch/arm/src/rp2040/rp2040_xosc.c
+  - These are created by referring the Pico SDK clock initialization.
+
+- arch/arm/src/rp2040/rp2040_pio.c
+- arch/arm/src/rp2040/rp2040_pio.h
+- arch/arm/src/rp2040/rp2040_pio_instructions.h
+  - These provide the similar APIs to Pico SDK's hardware_pio APIs.
+
+- arch/arm/src/rp2040/hardware/*.h
+  - These are generated from rp2040.svd originally provided in Pico SDK.
diff --git 
a/Documentation/platforms/arm/rp2040/boards/seeed-xiao-rp2040/index.rst 
b/Documentation/platforms/arm/rp2040/boards/seeed-xiao-rp2040/index.rst
new file mode 100644
index 0000000000..07f22378c0
--- /dev/null
+++ b/Documentation/platforms/arm/rp2040/boards/seeed-xiao-rp2040/index.rst
@@ -0,0 +1,98 @@
+========================
+Seeed Studio Xiao RP2040
+========================
+
+The `Seeed Studio Xiao RP2040 <https://wiki.seeedstudio.com/XIAO-RP2040/>`_ is 
a general purpose board supplied by
+Seeed Studio and it is compatible with the Raspberry Pi RP2040 ecosystem as 
they share the same RP2040 chip.
+
+.. figure:: seeed-xiao-rp2040.jpg
+   :align: center
+
+Features
+========
+
+* RP2040 microcontroller chip
+* Dual-core ARM Cortex M0+ processor, flexible clock running up to 133 MHz
+* 264KB of SRAM, and 2MB of onboard Flash memory
+* 11 digital pins, 4 analog pins, 11 PWM Pins
+* 1 I2C interface, 1 UART interface, 1 SPI interface, 1 SWD Bonding pad 
interface
+* USB Type-C interface
+* 1 user LED, 1 power LED, two LEDs for serial port downloading, 1 RGB LED
+* 1 RESET button, 1 BOOT button
+
+Serial Console
+==============
+
+By default a serial console appears on pins 6 (TX GPIO0) and pin 7
+(RX GPIO1).  This console runs a 115200-8N1.
+The board can be configured to use the USB connection as the serial console.
+
+LEDs
+====
+
+There are 2 LEDs available for user:
+
+- A RGB LED connected to GPIO16 (PIN_LED_G), GPIO17 (PIN_LED_R), GPIO25 
(PIN_LED_B).
+- A NeoPixel RGB LED connected to GPIO11 (NEOPIXEL_POWER) and GPIO12 
(PIN_NEOPIXEL).
+
+Buttons
+=======
+
+There are 2 buttons available:
+
+A RESET button and a BOOT button, which if held down when power is first
+applied to the board, will cause the RP2040 to boot into programming
+mode and appear as a storage device to a computer connected via USB.
+Saving a .UF2 file to this device will replace the Flash ROM contents
+on the RP2040.
+
+
+Pin Mapping
+===========
+Pads numbered anticlockwise from USB connector.
+
+===== ========== ==========
+Pad   Signal     Notes
+===== ========== ==========
+0     GPI26      D0/A0
+1     GPI27      D1/A1
+2     GPI28      D2/A2
+3     GPI29      D3/A3
+4     GPIO6      D4/SDA
+5     GPIO7      D5/SCL
+6     GPIO0      Default TX for UART0 serial console
+7     GPIO1      Default RX for UART1 serial console/CSn
+8     GPIO2      D8/SCK
+9     GPIO3      D10/MOSI
+10    GPIO4      D9/MicroSD
+11    3V3        Power output to peripherals
+12    Ground
+13    VIN        +5V Supply to board
+===== ========== ==========
+
+Power Supply
+============
+For general I/O pins:
+
+Working voltage of MCU is 3.3V. Voltage input connected to general I/O pins
+may cause chip damage if it' higher than 3.3V.
+
+For power supply pins:
+
+The built-in DC-DC converter circuit able to change 5V voltage into 3.3V allows
+to power the device with a 5V supply via VIN-PIN and via the USB connector.
+
+Configurations
+==============
+
+nsh
+---
+
+Basic NuttShell configuration (console enabled in UART0, at 115200 bps).
+
+
+README.txt
+==========
+
+.. include:: README.txt
+   :literal:
diff --git 
a/Documentation/platforms/arm/rp2040/boards/seeed-xiao-rp2040/seeed-xiao-rp2040.jpg
 
b/Documentation/platforms/arm/rp2040/boards/seeed-xiao-rp2040/seeed-xiao-rp2040.jpg
new file mode 100644
index 0000000000..c07ef5afdc
Binary files /dev/null and 
b/Documentation/platforms/arm/rp2040/boards/seeed-xiao-rp2040/seeed-xiao-rp2040.jpg
 differ
diff --git a/LICENSE b/LICENSE
index ebdd4319f8..14fd8da31e 100644
--- a/LICENSE
+++ b/LICENSE
@@ -8506,3 +8506,39 @@ Documentation/_extensions/warnings_filter.py
 ============================================
 Copyright (c) 2021 Nordic Semiconductor ASA
 SPDX-License-Identifier: Apache-2.0
+
+arch/arm/src/rp2040/rp2040_clock.c
+arch/arm/src/rp2040/rp2040_pll.c
+arch/arm/src/rp2040/rp2040_xosc.c
+arch/arm/src/rp2040/rp2040_pio.c
+arch/arm/src/rp2040/rp2040_pio.h
+arch/arm/src/rp2040/rp2040_pio_instructions.h
+arch/arm/src/rp2040/hardware/*.h
+=============================================
+
+Copyright 2020 (c) 2020 Raspberry Pi (Trading) Ltd.
+
+Redistribution and use in source and binary forms, with or without 
modification,
+are permitted provided that the following conditions are met:
+
+1. Redistributions of source code must retain the above copyright notice,
+this list of conditions and the following disclaimer.
+
+2. Redistributions in binary form must reproduce the above copyright notice,
+this list of conditions and the following disclaimer in the documentation
+and/or other materials provided with the distribution.
+
+3. Neither the name of the copyright holder nor the names of its contributors
+may be used to endorse or promote products derived from this software without
+specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 
DISCLAIMED.
+IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY 
DIRECT,
+INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 
DATA,
+OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 
LIABILITY,
+WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 
OTHERWISE)
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 
POSSIBILITY
+OF SUCH DAMAGE.
diff --git a/boards/Kconfig b/boards/Kconfig
index 24417ad78b..e8565a5639 100644
--- a/boards/Kconfig
+++ b/boards/Kconfig
@@ -1850,6 +1850,13 @@ config ARCH_BOARD_ADAFRUIT_FEATHER_RP2040
                This is a port to the Adafruit Feather RP2040 board.
                Support is derived from Raspberry Pi Pico support.
 
+config ARCH_BOARD_SEEED_XIAO_RP2040
+       bool "Seeed Studio XIAO RP2040 board"
+       depends on ARCH_CHIP_RP2040
+       ---help---
+               This is a port to the Seeed Studio XIAO RP2040 board.
+               Support is derived from Raspberry Pi Pico support.
+
 config ARCH_BOARD_ADAFRUIT_KB2040
        bool "Adafruit KB2040 board"
        depends on ARCH_CHIP_RP2040
@@ -3223,6 +3230,7 @@ config ARCH_BOARD
        default "raspberrypi-pico-w"        if ARCH_BOARD_RASPBERRYPI_PICO_W
        default "pimoroni-tiny2040"         if ARCH_BOARD_PIMORONI_TINY2040
        default "adafruit-feather-rp2040"   if 
ARCH_BOARD_ADAFRUIT_FEATHER_RP2040
+       default "seeed-xiao-rp2040"         if ARCH_BOARD_SEEED_XIAO_RP2040
        default "adafruit-kb2040"           if ARCH_BOARD_ADAFRUIT_KB2040
        default "adafruit-qt-py-rp2040"     if ARCH_BOARD_ADAFRUIT_QT_PY_RP2040
        default "waveshare-rp2040-lcd-1.28" if 
ARCH_BOARD_WAVESHARE_RP2040_LCD_1_28
@@ -3628,6 +3636,9 @@ endif
 if ARCH_BOARD_ADAFRUIT_FEATHER_RP2040
 source "boards/arm/rp2040/adafruit-feather-rp2040/Kconfig"
 endif
+if ARCH_BOARD_SEEED_XIAO_RP2040
+source "boards/arm/rp2040/seeed-xiao-rp2040/Kconfig"
+endif
 if ARCH_BOARD_ADAFRUIT_KB2040
 source "boards/arm/rp2040/adafruit-kb2040/Kconfig"
 endif
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/Kconfig 
b/boards/arm/rp2040/seeed-xiao-rp2040/Kconfig
new file mode 100644
index 0000000000..3b04b20128
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/Kconfig
@@ -0,0 +1,8 @@
+#
+# For a description of the syntax of this configuration file,
+# see the file kconfig-language.txt in the NuttX tools repository.
+#
+
+if ARCH_BOARD_SEEED_XIAO_RP2040
+
+endif
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/configs/nsh/defconfig 
b/boards/arm/rp2040/seeed-xiao-rp2040/configs/nsh/defconfig
new file mode 100644
index 0000000000..6d26a10736
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/configs/nsh/defconfig
@@ -0,0 +1,47 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed 
.config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that 
includes your
+# modifications.
+#
+# CONFIG_LIBC_LONG_LONG is not set
+# CONFIG_NSH_ARGCAT is not set
+# CONFIG_NSH_CMDOPT_HEXDUMP is not set
+# CONFIG_NSH_DISABLE_DATE is not set
+# CONFIG_NSH_DISABLE_LOSMART is not set
+# CONFIG_STANDARD_SERIAL is not set
+CONFIG_ARCH="arm"
+CONFIG_ARCH_BOARD="seeed-xiao-rp2040"
+CONFIG_ARCH_BOARD_SEEED_XIAO_RP2040=y
+CONFIG_ARCH_CHIP="rp2040"
+CONFIG_ARCH_CHIP_RP2040=y
+CONFIG_ARCH_RAMVECTORS=y
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_BOARDCTL_RESET=y
+CONFIG_BOARD_LOOPSPERMSEC=10450
+CONFIG_BUILTIN=y
+CONFIG_DEBUG_FULLOPT=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_EXAMPLES_HELLO=y
+CONFIG_FS_PROCFS=y
+CONFIG_FS_PROCFS_REGISTER=y
+CONFIG_INIT_ENTRYPOINT="nsh_main"
+CONFIG_NFILE_DESCRIPTORS_PER_BLOCK=6
+CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_NSH_READLINE=y
+CONFIG_RAM_SIZE=270336
+CONFIG_RAM_START=0x20000000
+CONFIG_READLINE_CMD_HISTORY=y
+CONFIG_RR_INTERVAL=200
+CONFIG_SCHED_WAITPID=y
+CONFIG_START_DAY=9
+CONFIG_START_MONTH=2
+CONFIG_START_YEAR=2021
+CONFIG_SYSLOG_CONSOLE=y
+CONFIG_SYSTEM_NSH=y
+CONFIG_TESTING_GETPRIME=y
+CONFIG_TESTING_OSTEST=y
+CONFIG_UART0_SERIAL_CONSOLE=y
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/include/board.h 
b/boards/arm/rp2040/seeed-xiao-rp2040/include/board.h
new file mode 100644
index 0000000000..58b0f5a607
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/include/board.h
@@ -0,0 +1,116 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/include/board.h
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+#ifndef __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_BOARD_H
+#define __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_BOARD_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "rp2040_i2cdev.h"
+#include "rp2040_spidev.h"
+#include "rp2040_i2sdev.h"
+
+#include "rp2040_spisd.h"
+
+#ifndef __ASSEMBLY__
+#  include <stdint.h>
+#endif
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Clocking *****************************************************************/
+
+#define MHZ                     1000000
+
+#define BOARD_XOSC_FREQ         (12 * MHZ)
+#define BOARD_PLL_SYS_FREQ      (125 * MHZ)
+#define BOARD_PLL_USB_FREQ      (48 * MHZ)
+
+#define BOARD_REF_FREQ          (12 * MHZ)
+#define BOARD_SYS_FREQ          (125 * MHZ)
+#define BOARD_PERI_FREQ         (125 * MHZ)
+#define BOARD_USB_FREQ          (48 * MHZ)
+#define BOARD_ADC_FREQ          (48 * MHZ)
+#define BOARD_RTC_FREQ          46875
+
+#define BOARD_UART_BASEFREQ     BOARD_PERI_FREQ
+
+#define BOARD_TICK_CLOCK        (1 * MHZ)
+
+/* GPIO definitions *********************************************************/
+
+#define BOARD_GPIO_LED_PIN      25
+#define BOARD_NGPIOOUT          1
+#define BOARD_NGPIOIN           1
+#define BOARD_NGPIOINT          1
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: rp2040_boardearlyinitialize
+ *
+ * Description:
+ *
+ ****************************************************************************/
+
+void rp2040_boardearlyinitialize(void);
+
+/****************************************************************************
+ * Name: rp2040_boardinitialize
+ *
+ * Description:
+ *
+ ****************************************************************************/
+
+void rp2040_boardinitialize(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+#endif /* __ASSEMBLY__ */
+#endif /* __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_BOARD_H */
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_i2cdev.h 
b/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_i2cdev.h
new file mode 100644
index 0000000000..f6f8fa6edb
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_i2cdev.h
@@ -0,0 +1,72 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_i2cdev.h
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+#ifndef __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_I2CDEV_H
+#define __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_I2CDEV_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <stdint.h>
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_i2cdev_initialize
+ *
+ * Description:
+ *   Initialize i2c driver and register the /dev/i2c device.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_RP2040_I2C_DRIVER
+int board_i2cdev_initialize(int bus);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_I2CDEV_H */
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_i2sdev.h 
b/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_i2sdev.h
new file mode 100644
index 0000000000..903d9d2143
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_i2sdev.h
@@ -0,0 +1,72 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_i2sdev.h
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+#ifndef __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_I2SDEV_H
+#define __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_I2SDEV_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <stdint.h>
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_i2sdev_initialize
+ *
+ * Description:
+ *   Initialize i2s driver and register the /dev/audio/pcm0 device.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_RP2040_I2S
+int board_i2sdev_initialize(int bus);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_I2SDEV_H */
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_spidev.h 
b/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_spidev.h
new file mode 100644
index 0000000000..59e473782e
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_spidev.h
@@ -0,0 +1,69 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_spidev.h
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+#ifndef __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_SPIDEV_H
+#define __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_SPIDEV_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_spidev_initialize
+ *
+ * Description:
+ *   Initialize spi driver and register the /dev/spi device.
+ *
+ ****************************************************************************/
+
+int board_spidev_initialize(int bus);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_SPIDEV_H */
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_spisd.h 
b/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_spisd.h
new file mode 100644
index 0000000000..a033e3b0fb
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_spisd.h
@@ -0,0 +1,83 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/include/rp2040_spisd.h
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+#ifndef __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_SPISD_H
+#define __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_SPISD_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_spisd_initialize
+ *
+ * Description:
+ *   Initialize the SPI-based SD card.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_RP2040_SPISD
+int board_spisd_initialize(int minor, int bus);
+#endif
+
+/****************************************************************************
+ * Name: board_spisd_status
+ *
+ * Description:
+ *   Get the status whether SD Card is present or not.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_RP2040_SPISD
+uint8_t board_spisd_status(struct spi_dev_s *dev, uint32_t devid);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __BOARDS_ARM_RP2040_SEEED_XIAO_INCLUDE_RP2040_SPISD_H */
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/scripts/Make.defs 
b/boards/arm/rp2040/seeed-xiao-rp2040/scripts/Make.defs
new file mode 100644
index 0000000000..f99456ce85
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/scripts/Make.defs
@@ -0,0 +1,45 @@
+############################################################################
+# boards/arm/rp2040/seeed-xiao-rp2040/scripts/Make.defs
+#
+# Licensed to the Apache Software Foundation (ASF) under one or more
+# contributor license agreements.  See the NOTICE file distributed with
+# this work for additional information regarding copyright ownership.  The
+# ASF licenses this file to you under the Apache License, Version 2.0 (the
+# "License"); you may not use this file except in compliance with the
+# License.  You may obtain a copy of the License at
+#
+#   http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+# License for the specific language governing permissions and limitations
+# under the License.
+#
+############################################################################
+
+include $(TOPDIR)/.config
+include $(TOPDIR)/tools/Config.mk
+include $(TOPDIR)/tools/rp2040/Config.mk
+include $(TOPDIR)/arch/arm/src/armv6-m/Toolchain.defs
+
+ifeq ($(CONFIG_RP2040_FLASH_BOOT),y)
+  LDSCRIPT = seeed-xiao-rp2040-flash.ld
+else
+  LDSCRIPT = seeed-xiao-rp2040-sram.ld
+endif
+
+ARCHSCRIPT += $(BOARD_DIR)$(DELIM)scripts$(DELIM)$(LDSCRIPT)
+
+ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
+
+CFLAGS := $(ARCHCFLAGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) 
$(ARCHDEFINES) $(EXTRAFLAGS) -pipe
+CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
+CXXFLAGS := $(ARCHCXXFLAGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) 
$(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRAFLAGS) -pipe
+CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
+CPPFLAGS := $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRAFLAGS)
+AFLAGS := $(CFLAGS) -D__ASSEMBLY__
+
+NXFLATLDFLAGS1 = -r -d -warn-common
+NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) 
-T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections
+LDNXFLATFLAGS = -e main -s 2048
diff --git 
a/boards/arm/rp2040/seeed-xiao-rp2040/scripts/seeed-xiao-rp2040-flash.ld 
b/boards/arm/rp2040/seeed-xiao-rp2040/scripts/seeed-xiao-rp2040-flash.ld
new file mode 100644
index 0000000000..5827803163
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/scripts/seeed-xiao-rp2040-flash.ld
@@ -0,0 +1,119 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/scripts/seeed-xiao-rp2040-flash.ld
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+MEMORY
+{
+  flash (rx) : ORIGIN = 0x10000000, LENGTH = 2048K
+  sram (rwx) : ORIGIN = 0x20000000, LENGTH = 264K
+}
+
+OUTPUT_ARCH(arm)
+EXTERN(_vectors)
+ENTRY(_stext)
+
+SECTIONS
+{
+    .flash_begin : {
+        __flash_binary_start = .;
+    } > flash
+
+    .boot2 : {
+        __boot2_start__ = .;
+        KEEP (*(.boot2))
+        __boot2_end__ = .;
+    } > flash
+
+    .text : {
+        _stext = ABSOLUTE(.);
+        *(.vectors)
+        *(.text .text.*)
+        *(.fixup)
+        *(.gnu.warning)
+        *(.rodata .rodata.*)
+        *(.gnu.linkonce.t.*)
+        *(.glue_7)
+        *(.glue_7t)
+        *(.got)
+        *(.gcc_except_table)
+        *(.gnu.linkonce.r.*)
+        _etext = ABSOLUTE(.);
+    } > flash
+
+    .init_section : {
+        _sinit = ABSOLUTE(.);
+        KEEP(*(SORT_BY_INIT_PRIORITY(.init_array.*) 
SORT_BY_INIT_PRIORITY(.ctors.*)))
+        KEEP(*(.init_array .ctors))
+        _einit = ABSOLUTE(.);
+    } > flash
+
+    .ARM.extab : {
+        *(.ARM.extab*)
+    } > flash
+
+    __exidx_start = ABSOLUTE(.);
+    .ARM.exidx : {
+        *(.ARM.exidx*)
+    } > flash
+    __exidx_end = ABSOLUTE(.);
+
+    _eronly = ABSOLUTE(.);
+
+    .ram_vectors (COPY) : {
+        *(.ram_vectors)
+    } > sram
+
+    .data : {
+        _sdata = ABSOLUTE(.);
+        *(.data .data.*)
+        *(.gnu.linkonce.d.*)
+        *(.ram_code.*)
+        CONSTRUCTORS
+        . = ALIGN(4);
+        _edata = ABSOLUTE(.);
+    } > sram AT > flash
+
+    .flash_section : {
+        . = ALIGN(4*1024);
+        *(.flash.*)
+    } > flash
+
+    .bss : {
+        _sbss = ABSOLUTE(.);
+        *(.bss .bss.*)
+        *(.gnu.linkonce.b.*)
+        *(COMMON)
+        . = ALIGN(4);
+        _ebss = ABSOLUTE(.);
+    } > sram
+
+    /* Stabs debugging sections. */
+    .stab 0 : { *(.stab) }
+    .stabstr 0 : { *(.stabstr) }
+    .stab.excl 0 : { *(.stab.excl) }
+    .stab.exclstr 0 : { *(.stab.exclstr) }
+    .stab.index 0 : { *(.stab.index) }
+    .stab.indexstr 0 : { *(.stab.indexstr) }
+    .comment 0 : { *(.comment) }
+    .debug_abbrev 0 : { *(.debug_abbrev) }
+    .debug_info 0 : { *(.debug_info) }
+    .debug_line 0 : { *(.debug_line) }
+    .debug_pubnames 0 : { *(.debug_pubnames) }
+    .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git 
a/boards/arm/rp2040/seeed-xiao-rp2040/scripts/seeed-xiao-rp2040-sram.ld 
b/boards/arm/rp2040/seeed-xiao-rp2040/scripts/seeed-xiao-rp2040-sram.ld
new file mode 100644
index 0000000000..cdca5a44a8
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/scripts/seeed-xiao-rp2040-sram.ld
@@ -0,0 +1,105 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/scripts/seeed-xiao-rp2040-sram.ld
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+MEMORY
+{
+  flash (rx) : ORIGIN = 0x10000000, LENGTH = 2048K
+  sram (rwx) : ORIGIN = 0x20000000, LENGTH = 264K
+}
+
+OUTPUT_ARCH(arm)
+EXTERN(_vectors)
+ENTRY(_stext)
+
+SECTIONS
+{
+    .text : {
+        _stext = ABSOLUTE(.);
+        rp2040_start.o(.text)
+        . = ALIGN(256);
+        *(.vectors)
+        *(.text .text.*)
+        *(.fixup)
+        *(.gnu.warning)
+        *(.rodata .rodata.*)
+        *(.gnu.linkonce.t.*)
+        *(.glue_7)
+        *(.glue_7t)
+        *(.got)
+        *(.gcc_except_table)
+        *(.gnu.linkonce.r.*)
+        _etext = ABSOLUTE(.);
+    } > sram
+
+    .init_section : {
+        _sinit = ABSOLUTE(.);
+        KEEP(*(SORT_BY_INIT_PRIORITY(.init_array.*) 
SORT_BY_INIT_PRIORITY(.ctors.*)))
+        KEEP(*(.init_array .ctors))
+        _einit = ABSOLUTE(.);
+    } > sram
+
+    .ARM.extab : {
+        *(.ARM.extab*)
+    } > sram
+
+    __exidx_start = ABSOLUTE(.);
+    .ARM.exidx : {
+        *(.ARM.exidx*)
+    } > sram
+    __exidx_end = ABSOLUTE(.);
+
+    .data : {
+        _sdata = ABSOLUTE(.);
+        *(.data .data.*)
+        *(.gnu.linkonce.d.*)
+        *(.ram_code.*)
+        CONSTRUCTORS
+        . = ALIGN(4);
+        _edata = ABSOLUTE(.);
+    } > sram
+
+    .flash_section : {
+        . = ALIGN(4*1024);
+        *(.flash.*)
+    } > flash
+
+    .bss : {
+        _sbss = ABSOLUTE(.);
+        *(.bss .bss.*)
+        *(.gnu.linkonce.b.*)
+        *(COMMON)
+        . = ALIGN(4);
+        _ebss = ABSOLUTE(.);
+    } > sram
+
+    /* Stabs debugging sections. */
+    .stab 0 : { *(.stab) }
+    .stabstr 0 : { *(.stabstr) }
+    .stab.excl 0 : { *(.stab.excl) }
+    .stab.exclstr 0 : { *(.stab.exclstr) }
+    .stab.index 0 : { *(.stab.index) }
+    .stab.indexstr 0 : { *(.stab.indexstr) }
+    .comment 0 : { *(.comment) }
+    .debug_abbrev 0 : { *(.debug_abbrev) }
+    .debug_info 0 : { *(.debug_info) }
+    .debug_line 0 : { *(.debug_line) }
+    .debug_pubnames 0 : { *(.debug_pubnames) }
+    .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/src/Make.defs 
b/boards/arm/rp2040/seeed-xiao-rp2040/src/Make.defs
new file mode 100644
index 0000000000..1988bff080
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/src/Make.defs
@@ -0,0 +1,33 @@
+############################################################################
+# boards/arm/rp2040/seeed-xiao-rp2040/src/Make.defs
+#
+# Licensed to the Apache Software Foundation (ASF) under one or more
+# contributor license agreements.  See the NOTICE file distributed with
+# this work for additional information regarding copyright ownership.  The
+# ASF licenses this file to you under the Apache License, Version 2.0 (the
+# "License"); you may not use this file except in compliance with the
+# License.  You may obtain a copy of the License at
+#
+#   http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+# License for the specific language governing permissions and limitations
+# under the License.
+#
+############################################################################
+
+include $(TOPDIR)/Make.defs
+
+CSRCS = rp2040_boardinitialize.c
+CSRCS += rp2040_appinit.c
+CSRCS += rp2040_bringup.c
+
+ifeq ($(CONFIG_DEV_GPIO),y)
+CSRCS += rp2040_gpio.c
+endif
+
+DEPPATH += --dep-path board
+VPATH += :board
+CFLAGS += 
${INCDIR_PREFIX}$(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)board
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_appinit.c 
b/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_appinit.c
new file mode 100644
index 0000000000..f11e2e7343
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_appinit.c
@@ -0,0 +1,76 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_appinit.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <nuttx/board.h>
+
+#include "rp2040_pico.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_app_initialize
+ *
+ * Description:
+ *   Perform application specific initialization.  This function is never
+ *   called directly from application code, but only indirectly via the
+ *   (non-standard) boardctl() interface using the command BOARDIOC_INIT.
+ *
+ * Input Parameters:
+ *   arg - The boardctl() argument is passed to the board_app_initialize()
+ *         implementation without modification.  The argument has no
+ *         meaning to NuttX; the meaning of the argument is a contract
+ *         between the board-specific initialization logic and the
+ *         matching application logic.  The value could be such things as a
+ *         mode enumeration value, a set of DIP switch switch settings, a
+ *         pointer to configuration data read from a file or serial FLASH,
+ *         or whatever you would like to do with it.  Every implementation
+ *         should accept zero/NULL as a default configuration.
+ *
+ * Returned Value:
+ *   Zero (OK) is returned on success; a negated errno value is returned on
+ *   any failure to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+int board_app_initialize(uintptr_t arg)
+{
+#ifdef CONFIG_BOARD_LATE_INITIALIZE
+  /* Board initialization already performed by board_late_initialize() */
+
+  return OK;
+#else
+  /* Perform board-specific initialization */
+
+  return rp2040_bringup();
+#endif
+}
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_boardinitialize.c 
b/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_boardinitialize.c
new file mode 100644
index 0000000000..3f4df88bd2
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_boardinitialize.c
@@ -0,0 +1,87 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_boardinitialize.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+
+#include <nuttx/board.h>
+#include <arch/board/board.h>
+
+#include "arm_internal.h"
+#include "rp2040_gpio.h"
+
+#ifdef CONFIG_ARCH_BOARD_COMMON
+#include "rp2040_common_initialize.h"
+#endif /* CONFIG_ARCH_BOARD_COMMON */
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: rp2040_boardearlyinitialize
+ *
+ * Description:
+ *
+ ****************************************************************************/
+
+void rp2040_boardearlyinitialize(void)
+{
+  #ifdef CONFIG_ARCH_BOARD_COMMON
+  rp2040_common_earlyinitialize();
+  #endif
+
+  /* --- Place any board specific early initialization here --- */
+
+  /* Set board LED pin */
+
+  rp2040_gpio_init(BOARD_GPIO_LED_PIN);
+  rp2040_gpio_setdir(BOARD_GPIO_LED_PIN, true);
+  rp2040_gpio_put(BOARD_GPIO_LED_PIN, true);
+}
+
+/****************************************************************************
+ * Name: rp2040_boardinitialize
+ *
+ * Description:
+ *
+ ****************************************************************************/
+
+void rp2040_boardinitialize(void)
+{
+  #ifdef CONFIG_ARCH_BOARD_COMMON
+  rp2040_common_initialize();
+  #endif
+
+  /* --- Place any board specific initialization here --- */
+}
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_bringup.c 
b/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_bringup.c
new file mode 100644
index 0000000000..96380f9f52
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_bringup.c
@@ -0,0 +1,63 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_bringup.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+#include <stddef.h>
+
+#include <nuttx/fs/fs.h>
+
+#include <arch/board/board.h>
+
+#include "rp2040_pico.h"
+
+#ifdef CONFIG_ARCH_BOARD_COMMON
+#include "rp2040_common_bringup.h"
+#endif /* CONFIG_ARCH_BOARD_COMMON */
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: rp2040_bringup
+ ****************************************************************************/
+
+int rp2040_bringup(void)
+{
+#ifdef CONFIG_ARCH_BOARD_COMMON
+
+  int ret = rp2040_common_bringup();
+  if (ret < 0)
+    {
+      return ret;
+    }
+
+#endif /* CONFIG_ARCH_BOARD_COMMON */
+
+  /* --- Place any board specific bringup code here --- */
+
+  return OK;
+}
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_gpio.c 
b/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_gpio.c
new file mode 100644
index 0000000000..ba00486b52
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_gpio.c
@@ -0,0 +1,392 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_gpio.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <syslog.h>
+#include <nuttx/irq.h>
+#include <arch/irq.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/ioexpander/gpio.h>
+
+#include <arch/board/board.h>
+
+#include "arm_internal.h"
+#include "chip.h"
+#include "rp2040_gpio.h"
+
+#if defined(CONFIG_DEV_GPIO) && !defined(CONFIG_GPIO_LOWER_HALF)
+
+/* Output pins. GPIO25 is onboard LED any other outputs could be used.
+ */
+
+#define GPIO_OUT1     25
+
+/* Input pins.
+ */
+
+#define GPIO_IN1      6
+
+/* Interrupt pins.
+ */
+
+#define GPIO_IRQPIN1  14
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct rp2040gpio_dev_s
+{
+  struct gpio_dev_s gpio;
+  uint8_t id;
+};
+
+struct rp2040gpint_dev_s
+{
+  struct rp2040gpio_dev_s rp2040gpio;
+  pin_interrupt_t callback;
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+#if BOARD_NGPIOOUT > 0
+static int gpout_read(struct gpio_dev_s *dev, bool *value);
+static int gpout_write(struct gpio_dev_s *dev, bool value);
+#endif
+
+#if BOARD_NGPIOIN > 0
+static int gpin_read(struct gpio_dev_s *dev, bool *value);
+#endif
+
+#if BOARD_NGPIOINT > 0
+static int gpint_read(struct gpio_dev_s *dev, bool *value);
+static int gpint_attach(struct gpio_dev_s *dev,
+                        pin_interrupt_t callback);
+static int gpint_enable(struct gpio_dev_s *dev, bool enable);
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+#if BOARD_NGPIOOUT > 0
+static const struct gpio_operations_s gpout_ops =
+{
+  .go_read   = gpout_read,
+  .go_write  = gpout_write,
+  .go_attach = NULL,
+  .go_enable = NULL,
+};
+
+/* This array maps the GPIO pins used as OUTPUT */
+
+static const uint32_t g_gpiooutputs[BOARD_NGPIOOUT] =
+{
+  GPIO_OUT1
+};
+
+static struct rp2040gpio_dev_s g_gpout[BOARD_NGPIOOUT];
+#endif
+
+#if BOARD_NGPIOIN > 0
+static const struct gpio_operations_s gpin_ops =
+{
+  .go_read   = gpin_read,
+  .go_write  = NULL,
+  .go_attach = NULL,
+  .go_enable = NULL,
+};
+
+/* This array maps the GPIO pins used as INTERRUPT INPUTS */
+
+static const uint32_t g_gpioinputs[BOARD_NGPIOIN] =
+{
+  GPIO_IN1
+};
+
+static struct rp2040gpio_dev_s g_gpin[BOARD_NGPIOIN];
+#endif
+
+#if BOARD_NGPIOINT > 0
+static const struct gpio_operations_s gpint_ops =
+{
+  .go_read   = gpint_read,
+  .go_write  = NULL,
+  .go_attach = gpint_attach,
+  .go_enable = gpint_enable,
+};
+
+/* This array maps the GPIO pins used as INTERRUPT INPUTS */
+
+static const uint32_t g_gpiointinputs[BOARD_NGPIOINT] =
+{
+  GPIO_IRQPIN1,
+};
+
+static struct rp2040gpint_dev_s g_gpint[BOARD_NGPIOINT];
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gpout_read
+ ****************************************************************************/
+
+#if BOARD_NGPIOOUT > 0
+static int gpout_read(struct gpio_dev_s *dev, bool *value)
+{
+  struct rp2040gpio_dev_s *rp2040gpio =
+    (struct rp2040gpio_dev_s *)dev;
+
+  DEBUGASSERT(rp2040gpio != NULL && value != NULL);
+  DEBUGASSERT(rp2040gpio->id < BOARD_NGPIOOUT);
+  gpioinfo("Reading...\n");
+
+  *value = rp2040_gpio_get(g_gpiooutputs[rp2040gpio->id]);
+  return OK;
+}
+
+/****************************************************************************
+ * Name: gpout_write
+ ****************************************************************************/
+
+static int gpout_write(struct gpio_dev_s *dev, bool value)
+{
+  struct rp2040gpio_dev_s *rp2040gpio =
+    (struct rp2040gpio_dev_s *)dev;
+
+  DEBUGASSERT(rp2040gpio != NULL);
+  DEBUGASSERT(rp2040gpio->id < BOARD_NGPIOOUT);
+  gpioinfo("Writing %d\n", (int)value);
+
+  rp2040_gpio_put(g_gpiooutputs[rp2040gpio->id], value);
+  return OK;
+}
+#endif
+
+/****************************************************************************
+ * Name: gpin_read
+ ****************************************************************************/
+
+#if BOARD_NGPIOIN > 0
+static int gpin_read(struct gpio_dev_s *dev, bool *value)
+{
+  struct rp2040gpio_dev_s *rp2040gpio =
+    (struct rp2040gpio_dev_s *)dev;
+
+  DEBUGASSERT(rp2040gpio != NULL && value != NULL);
+  DEBUGASSERT(rp2040gpio->id < BOARD_NGPIOIN);
+  gpioinfo("Reading... pin %d\n", (int)g_gpioinputs[rp2040gpio->id]);
+
+  *value = rp2040_gpio_get(g_gpioinputs[rp2040gpio->id]);
+  return OK;
+}
+#endif
+
+/****************************************************************************
+ * Name: rp2040gpio_interrupt
+ ****************************************************************************/
+
+#if BOARD_NGPIOINT > 0
+static int rp2040gpio_interrupt(int irq, void *context, void *arg)
+{
+  struct rp2040gpint_dev_s *rp2040gpint =
+    (struct rp2040gpint_dev_s *)arg;
+
+  DEBUGASSERT(rp2040gpint != NULL && rp2040gpint->callback != NULL);
+  gpioinfo("Interrupt! callback=%p\n", rp2040gpint->callback);
+
+  rp2040gpint->callback(&rp2040gpint->rp2040gpio.gpio,
+                       rp2040gpint->rp2040gpio.id);
+  return OK;
+}
+
+/****************************************************************************
+ * Name: gpint_read
+ ****************************************************************************/
+
+static int gpint_read(struct gpio_dev_s *dev, bool *value)
+{
+  struct rp2040gpint_dev_s *rp2040gpint =
+    (struct rp2040gpint_dev_s *)dev;
+
+  DEBUGASSERT(rp2040gpint != NULL && value != NULL);
+  DEBUGASSERT(rp2040gpint->rp2040gpio.id < BOARD_NGPIOINT);
+  gpioinfo("Reading int pin...\n");
+
+  *value = rp2040_gpio_get(g_gpiointinputs[rp2040gpint->rp2040gpio.id]);
+  return OK;
+}
+
+/****************************************************************************
+ * Name: gpint_attach
+ ****************************************************************************/
+
+static int gpint_attach(struct gpio_dev_s *dev,
+                        pin_interrupt_t callback)
+{
+  struct rp2040gpint_dev_s *rp2040gpint =
+    (struct rp2040gpint_dev_s *)dev;
+  int irq = g_gpiointinputs[rp2040gpint->rp2040gpio.id];
+  int ret;
+
+  gpioinfo("Attaching the callback\n");
+
+  /* Make sure the interrupt is disabled */
+
+  rp2040_gpio_disable_irq(irq);
+  ret = rp2040_gpio_irq_attach(irq,
+                               RP2040_GPIO_INTR_EDGE_LOW,
+                               rp2040gpio_interrupt,
+                               &g_gpint[rp2040gpint->rp2040gpio.id]);
+  if (ret < 0)
+    {
+      syslog(LOG_ERR, "ERROR: gpint_attach() failed: %d\n", ret);
+      return ret;
+    }
+
+  gpioinfo("Attach %p\n", callback);
+  rp2040gpint->callback = callback;
+  return OK;
+}
+
+/****************************************************************************
+ * Name: gpint_enable
+ ****************************************************************************/
+
+static int gpint_enable(struct gpio_dev_s *dev, bool enable)
+{
+  struct rp2040gpint_dev_s *rp2040gpint =
+    (struct rp2040gpint_dev_s *)dev;
+  int irq = g_gpiointinputs[rp2040gpint->rp2040gpio.id];
+
+  if (enable)
+    {
+      if (rp2040gpint->callback != NULL)
+        {
+          gpioinfo("Enabling the interrupt\n");
+
+          /* Configure the interrupt for rising edge */
+
+          rp2040_gpio_enable_irq(irq);
+        }
+    }
+  else
+    {
+      gpioinfo("Disable the interrupt\n");
+      rp2040_gpio_disable_irq(irq);
+    }
+
+  return OK;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: rp2040_dev_gpio_init
+ ****************************************************************************/
+
+int rp2040_dev_gpio_init(void)
+{
+  int i;
+  int pincount = 0;
+
+#if BOARD_NGPIOOUT > 0
+  for (i = 0; i < BOARD_NGPIOOUT; i++)
+    {
+      /* Setup and register the GPIO pin */
+
+      g_gpout[i].gpio.gp_pintype = GPIO_OUTPUT_PIN;
+      g_gpout[i].gpio.gp_ops     = &gpout_ops;
+      g_gpout[i].id              = i;
+      gpio_pin_register(&g_gpout[i].gpio, g_gpiooutputs[i]);
+
+      /* Configure the pins that will be used as output */
+
+      rp2040_gpio_init(g_gpiooutputs[i]);
+      rp2040_gpio_setdir(g_gpiooutputs[i], true);
+      rp2040_gpio_put(g_gpiooutputs[i], false);
+
+      pincount++;
+    }
+#endif
+
+  pincount = 0;
+
+#if BOARD_NGPIOIN > 0
+  for (i = 0; i < BOARD_NGPIOIN; i++)
+    {
+      /* Setup and register the GPIO pin */
+
+      g_gpin[i].gpio.gp_pintype = GPIO_INPUT_PIN;
+      g_gpin[i].gpio.gp_ops     = &gpin_ops;
+      g_gpin[i].id              = i;
+      gpio_pin_register(&g_gpin[i].gpio, g_gpioinputs[i]);
+
+      /* Configure the pins that will be used as INPUT */
+
+      rp2040_gpio_init(g_gpioinputs[i]);
+
+      pincount++;
+    }
+#endif
+
+  pincount = 0;
+
+#if BOARD_NGPIOINT > 0
+  for (i = 0; i < BOARD_NGPIOINT; i++)
+    {
+      /* Setup and register the GPIO pin */
+
+      g_gpint[i].rp2040gpio.gpio.gp_pintype = GPIO_INTERRUPT_PIN;
+      g_gpint[i].rp2040gpio.gpio.gp_ops     = &gpint_ops;
+      g_gpint[i].rp2040gpio.id              = i;
+      gpio_pin_register(&g_gpint[i].rp2040gpio.gpio, g_gpiointinputs[i]);
+
+      /* Configure the pins that will be used as interrupt input */
+
+      rp2040_gpio_init(g_gpiointinputs[i]);
+
+      /* pull-up = false : pull-down = true */
+
+      rp2040_gpio_set_pulls(g_gpiointinputs[i], false, true);
+
+      pincount++;
+    }
+#endif
+
+  return OK;
+}
+#endif /* CONFIG_DEV_GPIO && !CONFIG_GPIO_LOWER_HALF */
diff --git a/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_pico.h 
b/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_pico.h
new file mode 100644
index 0000000000..8e5c5ffaef
--- /dev/null
+++ b/boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_pico.h
@@ -0,0 +1,36 @@
+/****************************************************************************
+ * boards/arm/rp2040/seeed-xiao-rp2040/src/rp2040_pico.h
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+#ifndef __BOARDS_ARM_RP2040_SEEED_XIAO_SRC_RP2040_PICO_H
+#define __BOARDS_ARM_RP2040_SEEED_XIAO_SRC_RP2040_PICO_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+int rp2040_bringup(void);
+
+#ifdef CONFIG_DEV_GPIO
+int rp2040_dev_gpio_init(void);
+#endif
+
+#endif /* __BOARDS_ARM_RP2040_SEEED_XIAO_SRC_RP2040_PICO_H */

Reply via email to