diff --git a/CODEOWNERS b/CODEOWNERS index 41922203baf8e..8edc104af687b 100644 --- a/CODEOWNERS +++ b/CODEOWNERS @@ -44,6 +44,7 @@ /soc/arm/nuvoton/ @ssekar15 /soc/arm/nuvoton_npcx/ @MulinChao @WealianLiao @ChiHuaL /soc/arm/quicklogic_eos_s3/ @kowalewskijan @kgugala +/soc/arm/raspberrypi/ @yonsch /soc/arm/silabs_exx32/efm32pg1b/ @rdmeneze /soc/arm/silabs_exx32/efr32mg21/ @l-alfred /soc/arm/st_stm32/ @erwango @@ -118,6 +119,7 @@ /boards/arm/quick_feather/ @kowalewskijan @kgugala /boards/arm/rak4631_nrf52840/ @gpaquet85 /boards/arm/rak5010_nrf52840/ @gpaquet85 +/boards/arm/raspberrypi_pico/ @yonsch /boards/arm/ronoth_lodev/ @NorthernDean /boards/arm/xmc45_relax_kit/ @parthitce /boards/arm/sam4e_xpro/ @nandojve @@ -287,6 +289,7 @@ /drivers/serial/uart_mcux_iuart.c @Mani-Sadhasivam /drivers/serial/Kconfig.rtt @carlescufi @pkral78 /drivers/serial/uart_rtt.c @carlescufi @pkral78 +/drivers/serial/uart_raspberrypi.c @yonsch /drivers/serial/Kconfig.xlnx @wjliang /drivers/serial/uart_xlnx_ps.c @wjliang /drivers/serial/uart_xlnx_uartlite.c @henrikbrixandersen @@ -357,6 +360,7 @@ /dts/arm/nuvoton/npcx/ @MulinChao @WealianLiao @ChiHuaL /dts/arm/nxp/ @MaureenHelm @mmahadevan108 @dleach02 /dts/arm/microchip/ @franciscomunoz @albertofloyd @scottwcpg +/dts/arm/raspberrypi/ @yonsch /dts/arm/silabs/efm32_pg_1b.dtsi @rdmeneze /dts/arm/silabs/efm32gg11b* @oanerer /dts/arm/silabs/efm32_jg_pg* @chrta diff --git a/boards/arm/raspberrypi_pico/Kconfig.board b/boards/arm/raspberrypi_pico/Kconfig.board new file mode 100644 index 0000000000000..ac9d9661bbfe4 --- /dev/null +++ b/boards/arm/raspberrypi_pico/Kconfig.board @@ -0,0 +1,6 @@ +# Copyright (c) 2021 Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +config BOARD_RPI_PICO + bool "Raspberry Pi Pico Board" + depends on SOC_RP2040 diff --git a/boards/arm/raspberrypi_pico/Kconfig.defconfig b/boards/arm/raspberrypi_pico/Kconfig.defconfig new file mode 100644 index 0000000000000..fedfa48fc0873 --- /dev/null +++ b/boards/arm/raspberrypi_pico/Kconfig.defconfig @@ -0,0 +1,9 @@ +# Copyright (c) 2021 Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +if BOARD_RPI_PICO + +config BOARD + default "raspberrypi_pico" + +endif # BOARD_RPI_PICO diff --git a/boards/arm/raspberrypi_pico/board.cmake b/boards/arm/raspberrypi_pico/board.cmake new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/boards/arm/raspberrypi_pico/doc/img/raspberrypi_pico.png b/boards/arm/raspberrypi_pico/doc/img/raspberrypi_pico.png new file mode 100644 index 0000000000000..0b223bb334bd9 Binary files /dev/null and b/boards/arm/raspberrypi_pico/doc/img/raspberrypi_pico.png differ diff --git a/boards/arm/raspberrypi_pico/doc/index.rst b/boards/arm/raspberrypi_pico/doc/index.rst new file mode 100644 index 0000000000000..6c8a4bd930da4 --- /dev/null +++ b/boards/arm/raspberrypi_pico/doc/index.rst @@ -0,0 +1,49 @@ +.. _raspberrypi_pico: + +Raspberry Pi Pico +################# + +Overview +******** + +The Raspberry Pi Pico is a small, low-cost, versatile board from +Raspberry Pi. It is equipped with an RP2040 SoC, an on-board LED, +a USB connector, and an SWD inteface. The USB bootloader allows it +to be flashed without any adapter, in a drag-and-drop manner. +It is also possible to flash and debug the Pico with its SWD interface, +using an external adapter. + +Hardware +******** +- Dual core Arm Cortex-M0+ processor running up to 133MHz +- 264KB on-chip SRAM +- 2MB on-board QSPI flash with XIP capabilities +- 26 GPIO pins +- 3 Analog inputs +- 2 UART peripherals +- 2 SPI controllers +- 2 I2C controllers +- 16 PWM channels +- USB 1.1 controller (host/device) +- 8 Programmable I/O (PIO) for custom peripherals +- On-board LED + + +.. figure:: img/raspberrypi_pico.png + :width: 150px + :align: center + :alt: Raspberry Pi Pico + + Raspberry Pi Pico (Image courtesy of Raspberry Pi) + +Supported Features +================== + +The raspberrypi_pico board configuration supports the following +hardware features: + ++-----------+------------+----------------------+ +| Interface | Controller | Driver/Component | ++===========+============+======================+ +| UART | on-chip | serial port | ++-----------+------------+----------------------+ diff --git a/boards/arm/raspberrypi_pico/raspberrypi_pico.dts b/boards/arm/raspberrypi_pico/raspberrypi_pico.dts new file mode 100644 index 0000000000000..1d209ab0e0ef3 --- /dev/null +++ b/boards/arm/raspberrypi_pico/raspberrypi_pico.dts @@ -0,0 +1,61 @@ +/* + * Copyright (c) 2021 Yonatan Schachter + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/dts-v1/; + +#include + +/ { + chosen { + zephyr,sram = &sram0; + zephyr,flash = &flash0; + zephyr,console = &uart0; + }; + + leds { + compatible = "gpio-leds"; + led0: led_0 { + gpios = <&gpio0 25 GPIO_ACTIVE_LOW>; + label = "LED"; + }; + }; + + pwmleds { + compatible = "pwm-leds"; + pwm_led0: pwm_led_0 { + pwms = <&pwm0 25 0>; + label = "PWM LED0"; + }; + }; + + aliases { + led0 = &led0; + pwm-led0 = &pwm_led0; + }; +}; + +&flash0 { + /* 2MB of flash minus the 0x100 used for + * the second stage bootloader + */ + reg = <0x10000100 0x001fff00>; +}; + +&uart0 { + current-speed = <115200>; + status = "okay"; + tx-pin = <0>; + rx-pin = <1>; +}; + +&gpio0 { + status = "okay"; +}; + +&pwm0 { + status = "okay"; + prescaler = <255>; +}; diff --git a/boards/arm/raspberrypi_pico/raspberrypi_pico.yaml b/boards/arm/raspberrypi_pico/raspberrypi_pico.yaml new file mode 100644 index 0000000000000..cb29bdbb696f3 --- /dev/null +++ b/boards/arm/raspberrypi_pico/raspberrypi_pico.yaml @@ -0,0 +1,12 @@ +identifier: raspberrypi_pico +name: RaspberryPi-Pico +type: mcu +arch: arm +flash: 2048 +ram: 264 +toolchain: + - zephyr + - gnuarmemb + - xtools +supported: + - serial diff --git a/boards/arm/raspberrypi_pico/raspberrypi_pico_defconfig b/boards/arm/raspberrypi_pico/raspberrypi_pico_defconfig new file mode 100644 index 0000000000000..1afc52f3f1920 --- /dev/null +++ b/boards/arm/raspberrypi_pico/raspberrypi_pico_defconfig @@ -0,0 +1,9 @@ +CONFIG_SOC_SERIES_RP2XXX=y +CONFIG_SOC_RP2040=y +CONFIG_SYS_CLOCK_HW_CYCLES_PER_SEC=125000000 +CONFIG_RP2_FLASH_W25Q080=y +CONFIG_SERIAL=y +CONFIG_LOG=y +CONFIG_LOG_PRINTK=y +CONFIG_CONSOLE=y +CONFIG_UART_CONSOLE=y diff --git a/drivers/gpio/CMakeLists.txt b/drivers/gpio/CMakeLists.txt index 72064e8bceb2f..6b76e8032ebdf 100644 --- a/drivers/gpio/CMakeLists.txt +++ b/drivers/gpio/CMakeLists.txt @@ -26,6 +26,7 @@ zephyr_library_sources_ifdef(CONFIG_GPIO_SAM4L gpio_sam4l.c) zephyr_library_sources_ifdef(CONFIG_GPIO_SX1509B gpio_sx1509b.c) zephyr_library_sources_ifdef(CONFIG_GPIO_INTEL_APL gpio_intel_apl.c) zephyr_library_sources_ifdef(CONFIG_GPIO_STELLARIS gpio_stellaris.c) +zephyr_library_sources_ifdef(CONFIG_GPIO_RASPBERRYPI gpio_raspberrypi.c) zephyr_library_sources_ifdef(CONFIG_GPIO_RV32M1 gpio_rv32m1.c) zephyr_library_sources_ifdef(CONFIG_GPIO_HT16K33 gpio_ht16k33.c) zephyr_library_sources_ifdef(CONFIG_GPIO_LMP90XXX gpio_lmp90xxx.c) diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig index cb51450bb05f8..063fe2a28f049 100644 --- a/drivers/gpio/Kconfig +++ b/drivers/gpio/Kconfig @@ -67,6 +67,8 @@ source "drivers/gpio/Kconfig.xec" source "drivers/gpio/Kconfig.stellaris" +source "drivers/gpio/Kconfig.raspberrypi" + source "drivers/gpio/Kconfig.rv32m1" source "drivers/gpio/Kconfig.ht16k33" diff --git a/drivers/gpio/Kconfig.raspberrypi b/drivers/gpio/Kconfig.raspberrypi new file mode 100644 index 0000000000000..c08ffc3e3e9e8 --- /dev/null +++ b/drivers/gpio/Kconfig.raspberrypi @@ -0,0 +1,5 @@ +# Copyright (c) 2021 Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +config GPIO_RASPBERRYPI + bool "Raspberry Pi GPIO driver" diff --git a/drivers/gpio/gpio_raspberrypi.c b/drivers/gpio/gpio_raspberrypi.c new file mode 100644 index 0000000000000..7f4fc7bb2d855 --- /dev/null +++ b/drivers/gpio/gpio_raspberrypi.c @@ -0,0 +1,178 @@ +/* + * Copyright (c) 2021, Yonatan Schachter + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include +#include +#include + +#include "gpio_utils.h" + +#define DT_DRV_COMPAT raspberrypi_rp2_gpio + +#define IRQ_PRIORITY 0 +#define ALL_EVENTS (GPIO_IRQ_EDGE_FALL | GPIO_IRQ_EDGE_RISE \ + | GPIO_IRQ_LEVEL_LOW | GPIO_IRQ_LEVEL_HIGH) + +struct gpio_raspberrypi_config { + struct gpio_driver_config common; +}; + +struct gpio_raspberrypi_data { + struct gpio_driver_data common; + sys_slist_t callbacks; + uint32_t int_enabled_mask; +}; + +static int gpio_raspberrypi_configure(const struct device *dev, + gpio_pin_t pin, + gpio_flags_t flags) +{ + if (flags & GPIO_SINGLE_ENDED) { + return -ENOTSUP; + } + + gpio_init(pin); + + if (flags & GPIO_OUTPUT) { + gpio_set_dir(pin, GPIO_OUT); + + if (flags & GPIO_OUTPUT_INIT_HIGH) + gpio_put(pin, 1); + else if (flags & GPIO_OUTPUT_INIT_LOW) + gpio_put(pin, 0); + + } else if (flags & GPIO_INPUT) { + gpio_set_dir(pin, GPIO_IN); + if (flags & GPIO_PULL_UP) + gpio_pull_up(pin); + else if (flags & GPIO_PULL_DOWN) + gpio_pull_down(pin); + } + + return 0; +} + +static int gpio_raspberrypi_port_get_raw(const struct device *dev, uint32_t *value) +{ + *value = gpio_get_all(); + return 0; +} + +static int gpio_raspberrypi_port_set_masked_raw(const struct device *port, + uint32_t mask, uint32_t value) +{ + gpio_put_masked(mask, value); + return 0; +} + +static int gpio_raspberrypi_port_set_bits_raw(const struct device *port, + uint32_t pins) +{ + gpio_set_mask(pins); + return 0; +} + +static int gpio_raspberrypi_port_clear_bits_raw(const struct device *port, + uint32_t pins) +{ + gpio_clr_mask(pins); + return 0; +} + +static int gpio_raspberrypi_port_toggle_bits(const struct device *port, + uint32_t pins) +{ + gpio_xor_mask(pins); + return 0; +} + +static int gpio_raspberrypi_pin_interrupt_configure(const struct device *dev, + gpio_pin_t pin, + enum gpio_int_mode mode, + enum gpio_int_trig trig) +{ + uint32_t events = 0; + struct gpio_raspberrypi_data *data = dev->data; + + if (mode != GPIO_INT_DISABLE) { + if (mode & GPIO_INT_EDGE) { + if (trig & GPIO_INT_LOW_0) + events |= GPIO_IRQ_EDGE_FALL; + if (trig & GPIO_INT_HIGH_1) + events |= GPIO_IRQ_EDGE_RISE; + } else { + if (trig & GPIO_INT_LOW_0) + events |= GPIO_IRQ_LEVEL_LOW; + if (trig & GPIO_INT_HIGH_1) + events |= GPIO_IRQ_LEVEL_HIGH; + } + gpio_set_irq_enabled(pin, events, true); + } + WRITE_BIT(data->int_enabled_mask, pin, mode != GPIO_INT_DISABLE); + return 0; +} + +static int gpio_raspberrypi_manage_callback(const struct device *dev, + struct gpio_callback *callback, bool set) +{ + struct gpio_raspberrypi_data *data = dev->data; + + return gpio_manage_callback(&data->callbacks, callback, set); +} + +static const struct gpio_driver_api gpio_raspberrypi_driver_api = { + .pin_configure = gpio_raspberrypi_configure, + .port_get_raw = gpio_raspberrypi_port_get_raw, + .port_set_masked_raw = gpio_raspberrypi_port_set_masked_raw, + .port_set_bits_raw = gpio_raspberrypi_port_set_bits_raw, + .port_clear_bits_raw = gpio_raspberrypi_port_clear_bits_raw, + .port_toggle_bits = gpio_raspberrypi_port_toggle_bits, + .pin_interrupt_configure = gpio_raspberrypi_pin_interrupt_configure, + .manage_callback = gpio_raspberrypi_manage_callback, +}; + +static void gpio_raspberrypi_isr(const struct device *dev) +{ + struct gpio_raspberrypi_data *data = dev->data; + uint32_t pin; + uint32_t events; + io_irq_ctrl_hw_t *irq_ctrl_base; + io_rw_32 *status_reg; + + irq_ctrl_base = &iobank0_hw->proc0_irq_ctrl; + for (pin = 0; pin < NUM_BANK0_GPIOS; pin++) { + status_reg = &irq_ctrl_base->ints[pin / 8]; + events = (*status_reg >> 4 * (pin % 8)) & ALL_EVENTS; + if (events) { + gpio_acknowledge_irq(pin, ALL_EVENTS); + gpio_fire_callbacks(&data->callbacks, dev, BIT(pin)); + } + } +} + +static int gpio_raspberrypi_init(const struct device *dev) +{ + IRQ_CONNECT(IO_IRQ_BANK0, IRQ_PRIORITY, gpio_raspberrypi_isr, + DEVICE_DT_GET(DT_INST(0, raspberrypi_rp2_gpio)), 0); + irq_enable(IO_IRQ_BANK0); + return 0; +} + +#define GPIO_RASPBERRYPI_INIT(idx) \ +static const struct gpio_raspberrypi_config gpio_raspberrypi_##idx##_config = { \ +}; \ + \ +static struct gpio_raspberrypi_data gpio_raspberrypi_##idx##_data; \ + \ +DEVICE_DT_INST_DEFINE(idx, gpio_raspberrypi_init, NULL, \ + &gpio_raspberrypi_##idx##_data, \ + &gpio_raspberrypi_##idx##_config, \ + POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEFAULT, \ + &gpio_raspberrypi_driver_api); + +DT_INST_FOREACH_STATUS_OKAY(GPIO_RASPBERRYPI_INIT) diff --git a/drivers/pwm/CMakeLists.txt b/drivers/pwm/CMakeLists.txt index 00160a26bf8f6..aee68fdb5a0a2 100644 --- a/drivers/pwm/CMakeLists.txt +++ b/drivers/pwm/CMakeLists.txt @@ -13,6 +13,7 @@ zephyr_library_sources_ifdef(CONFIG_PWM_SAM pwm_sam.c) zephyr_library_sources_ifdef(CONFIG_PWM_MCUX pwm_mcux.c) zephyr_library_sources_ifdef(CONFIG_PWM_XEC pwm_mchp_xec.c) zephyr_library_sources_ifdef(CONFIG_PWM_LITEX pwm_litex.c) +zephyr_library_sources_ifdef(CONFIG_PWM_RASPBERRYPI pwm_raspberrypi.c) zephyr_library_sources_ifdef(CONFIG_PWM_RV32M1_TPM pwm_rv32m1_tpm.c) zephyr_library_sources_ifdef(CONFIG_PWM_MCUX_TPM pwm_mcux_tpm.c) zephyr_library_sources_ifdef(CONFIG_PWM_SAM0_TCC pwm_sam0_tcc.c) diff --git a/drivers/pwm/Kconfig b/drivers/pwm/Kconfig index 130cb1b0b5328..a4286222d9720 100644 --- a/drivers/pwm/Kconfig +++ b/drivers/pwm/Kconfig @@ -49,6 +49,8 @@ source "drivers/pwm/Kconfig.xec" source "drivers/pwm/Kconfig.litex" +source "drivers/pwm/Kconfig.raspberrypi" + source "drivers/pwm/Kconfig.rv32m1_tpm" source "drivers/pwm/Kconfig.mcux_tpm" diff --git a/drivers/pwm/Kconfig.raspberrypi b/drivers/pwm/Kconfig.raspberrypi new file mode 100644 index 0000000000000..e8424e1547933 --- /dev/null +++ b/drivers/pwm/Kconfig.raspberrypi @@ -0,0 +1,4 @@ +# SPDX-License-Identifier: Apache-2.0 + +config PWM_RASPBERRYPI + bool "Raspberry PWM driver" diff --git a/drivers/pwm/pwm_raspberrypi.c b/drivers/pwm/pwm_raspberrypi.c new file mode 100644 index 0000000000000..fa514ec4aa22e --- /dev/null +++ b/drivers/pwm/pwm_raspberrypi.c @@ -0,0 +1,155 @@ +/* + * Author: Radu Nicolae Pirea + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT raspberrypi_rp2_pwm + +#include +#include +#include +#include +LOG_MODULE_REGISTER(pwm_rpi, CONFIG_PWM_LOG_LEVEL); + +#define RPI_PWM_MAX_PINS 29 +#define RPI_PWM_MAX_CHANS 8 +#define RPI_PWM_MAX_CYCLES GENMASK(15, 0) +struct pwm_rpi_config { + mm_reg_t regs_base; + uint32_t prescaler; +}; + +struct pwm_rpi_data { + uint8_t pins[RPI_PWM_MAX_CHANS]; + uint8_t chans; +}; + +#define CHAN_OFF 0x14 +#define CSR_OFF 0x00 +#define DIV_OFF 0x04 +#define CTR_OFF 0x08 +#define CC_OFF 0x0C +#define TOP_OFF 0x10 + +#define CSR_CHAN_EN BIT(0) +#define CSR_CHAN_INV_A BIT(2) +#define CSR_CHAN_INV_B BIT(3) + +#define REG_ADDR(base, chan_id, reg) (base + CHAN_OFF * chan_id + reg##_OFF) + +#define DEV_CFG(dev) \ + ((const struct pwm_rpi_config * const)(dev)->config) + +#define PWM_CHAN_ID(pin) ((pwm >> 1) & 0x07) + +#define RPI_PWM_CLK_FREQ 125000000ULL + +static int pwm_rpi_get_cycles_per_sec(const struct device *dev, uint32_t pwm, + uint64_t *cycles) +{ + uint32_t prescaler = DEV_CFG(dev)->prescaler; + + *cycles = RPI_PWM_CLK_FREQ / (prescaler + 1); + return 0; +} + +static int pwm_rpi_pin_set(const struct device *dev, uint32_t pwm, + uint32_t period, uint32_t pulse, pwm_flags_t flags) +{ + mm_reg_t regs_base = DEV_CFG(dev)->regs_base; + struct pwm_rpi_data *data = dev->data; + uint32_t chan_id = PWM_CHAN_ID(pwm); + uint32_t csr; + + if (pwm > RPI_PWM_MAX_PINS) { + LOG_ERR("invalid PWM pin.\n"); + return -EINVAL; + } + + if (period > RPI_PWM_MAX_CYCLES) { + LOG_ERR("period > %lu\n", RPI_PWM_MAX_CYCLES); + return -EINVAL; + } + + if (period < pulse) { + LOG_ERR("period < pulses --- %u < %u\n", period, pulse); + return -EINVAL; + } + + if (data->chans & BIT(chan_id)) { + if (data->pins[chan_id] != pwm) + return -EBUSY; + } else { + data->chans |= BIT(chan_id); + data->pins[chan_id] = pwm; + } + + sys_write32(period, REG_ADDR(regs_base, chan_id, TOP)); + + if (pwm % 2) { + pulse <<= 16; + sys_write32(pulse, REG_ADDR(regs_base, chan_id, CC)); + } else { + sys_write32(pulse, REG_ADDR(regs_base, chan_id, CC)); + } + + csr = sys_read32(REG_ADDR(regs_base, chan_id, CSR)); + csr |= CSR_CHAN_EN; + + if (flags & PWM_POLARITY_INVERTED) { + if (pwm % 2) + csr |= CSR_CHAN_INV_B; + else + csr |= CSR_CHAN_INV_A; + } else { + if (pwm % 2) + csr &= ~CSR_CHAN_INV_B; + else + csr &= ~CSR_CHAN_INV_A; + } + + sys_write32(csr, REG_ADDR(regs_base, chan_id, CSR)); + gpio_set_function(pwm, GPIO_FUNC_PWM); + + return 0; +} + +static int pwm_rpi_init(const struct device *dev) +{ + mm_reg_t regs_base = DEV_CFG(dev)->regs_base; + uint32_t prescaler = DEV_CFG(dev)->prescaler; + struct pwm_rpi_data *data = dev->data; + int chan_id; + + data->chans = 0; + for (chan_id = 0; chan_id < 8; chan_id++) { + data->pins[chan_id] = 0; + sys_write32(prescaler << 4, REG_ADDR(regs_base, chan_id, DIV)); + } + + return 0; +} + +static const struct pwm_driver_api pwm_rpi_driver_api = { + .pin_set = pwm_rpi_pin_set, + .get_cycles_per_sec = pwm_rpi_get_cycles_per_sec, +}; + +#define PWM_RPI_INST_INIT(inst) \ + static const struct pwm_rpi_config pwm_rpi_config_##inst = { \ + .regs_base = (mm_reg_t)DT_INST_REG_ADDR(inst), \ + .prescaler = (uint8_t)DT_INST_PROP(inst, prescaler), \ + }; \ + \ + static struct pwm_rpi_data pwm_rpi_data_##inst; \ + \ + DEVICE_DT_INST_DEFINE(inst, \ + &pwm_rpi_init, NULL, \ + &pwm_rpi_data_##inst, \ + &pwm_rpi_config_##inst, \ + POST_KERNEL, \ + CONFIG_KERNEL_INIT_PRIORITY_DEVICE, \ + &pwm_rpi_driver_api); + +DT_INST_FOREACH_STATUS_OKAY(PWM_RPI_INST_INIT) diff --git a/drivers/serial/CMakeLists.txt b/drivers/serial/CMakeLists.txt index 51f792d61aed8..53aacc7aa7ca9 100644 --- a/drivers/serial/CMakeLists.txt +++ b/drivers/serial/CMakeLists.txt @@ -30,6 +30,7 @@ zephyr_library_sources_ifdef(CONFIG_UART_SAM0 uart_sam0.c) zephyr_library_sources_ifdef(CONFIG_UART_PSOC6 uart_psoc6.c) zephyr_library_sources_ifdef(CONFIG_UART_PL011 uart_pl011.c) zephyr_library_sources_ifdef(CONFIG_UART_RV32M1_LPUART uart_rv32m1_lpuart.c) +zephyr_library_sources_ifdef(CONFIG_UART_RASPBERRYPI uart_raspberrypi.c) zephyr_library_sources_ifdef(CONFIG_UART_LITEUART uart_liteuart.c) zephyr_library_sources_ifdef(CONFIG_UART_RTT_DRIVER uart_rtt.c) zephyr_library_sources_ifdef(CONFIG_UART_XLNX_PS uart_xlnx_ps.c) diff --git a/drivers/serial/Kconfig b/drivers/serial/Kconfig index a9fe9d234a8cf..2aa9932b369ac 100644 --- a/drivers/serial/Kconfig +++ b/drivers/serial/Kconfig @@ -120,6 +120,8 @@ source "drivers/serial/Kconfig.pl011" source "drivers/serial/Kconfig.rv32m1_lpuart" +source "drivers/serial/Kconfig.raspberrypi" + source "drivers/serial/Kconfig.litex" source "drivers/serial/Kconfig.rtt" diff --git a/drivers/serial/Kconfig.raspberrypi b/drivers/serial/Kconfig.raspberrypi new file mode 100644 index 0000000000000..7d579ddaf1ca7 --- /dev/null +++ b/drivers/serial/Kconfig.raspberrypi @@ -0,0 +1,6 @@ +# Copyright (c) 2021 Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +config UART_RASPBERRYPI + bool "Raspberry Pi UART driver" + select SERIAL_HAS_DRIVER diff --git a/drivers/serial/uart_raspberrypi.c b/drivers/serial/uart_raspberrypi.c new file mode 100644 index 0000000000000..3bcc3b4bb64f5 --- /dev/null +++ b/drivers/serial/uart_raspberrypi.c @@ -0,0 +1,77 @@ +/* + * Copyright (c) 2021, Yonatan Schachter + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include + +struct uart_rpi_config { + uart_inst_t *const uart_dev; + uint32_t baudrate; + uint32_t tx_pin; + uint32_t rx_pin; +}; + +struct uart_rpi_data { + +}; + +static int uart_rpi_poll_in(const struct device *dev, unsigned char *c) +{ + const struct uart_rpi_config *config = dev->config; + + if (!uart_is_readable(config->uart_dev)) + return -1; + + *c = (unsigned char)uart_get_hw(config->uart_dev)->dr; + return 0; +} + +static void uart_rpi_poll_out(const struct device *dev, unsigned char c) +{ + const struct uart_rpi_config *config = dev->config; + + uart_putc_raw(config->uart_dev, c); +} + +static int uart_rpi_init(const struct device *dev) +{ + const struct uart_rpi_config *config = dev->config; + + gpio_init(config->tx_pin); + gpio_init(config->rx_pin); + gpio_set_function(config->tx_pin, GPIO_FUNC_UART); + gpio_set_function(config->rx_pin, GPIO_FUNC_UART); + + return !uart_init(config->uart_dev, config->baudrate); +} + +static const struct uart_driver_api uart_rpi_driver_api = { + .poll_in = uart_rpi_poll_in, + .poll_out = uart_rpi_poll_out, +}; + +#undef DT_DRV_COMPAT +#define DT_DRV_COMPAT raspberrypi_rp2_uart + +#define RPI_UART_INIT(idx) \ + static const struct uart_rpi_config uart_rpi_cfg_##idx = { \ + .uart_dev = (uart_inst_t *)DT_INST_REG_ADDR(idx), \ + .baudrate = DT_INST_PROP(idx, current_speed), \ + .tx_pin = DT_INST_PROP(idx, tx_pin), \ + .rx_pin = DT_INST_PROP(idx, rx_pin), \ + }; \ + \ + static struct uart_rpi_data uart_rpi_data_##idx; \ + \ + DEVICE_DT_INST_DEFINE(idx, &uart_rpi_init, \ + device_pm_control_nop, \ + &uart_rpi_data_##idx, \ + &uart_rpi_cfg_##idx, PRE_KERNEL_1, \ + CONFIG_KERNEL_INIT_PRIORITY_DEVICE, \ + &uart_rpi_driver_api); + +DT_INST_FOREACH_STATUS_OKAY(RPI_UART_INIT) diff --git a/dts/arm/raspberrypi/rp2040.dtsi b/dts/arm/raspberrypi/rp2040.dtsi new file mode 100644 index 0000000000000..56f33022ee577 --- /dev/null +++ b/dts/arm/raspberrypi/rp2040.dtsi @@ -0,0 +1,90 @@ +/* + * Copyright (c) 2021 Yonatan Schachter + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include + +/ { + cpus { + #address-cells = <1>; + #size-cells = <0>; + + cpu0: cpu@0 { + compatible = "arm,cortex-m0+"; + reg = <0>; + }; + + cpu1: cpu@1 { + compatible = "arm,cortex-m0+"; + reg = <1>; + }; + }; + + sram0: memory@20000000 { + compatible = "mmio-sram"; + reg = <0x20000000 DT_SIZE_K(264)>; + }; + + /* Flash starts at 0x10000000 but the first 0x100 bytes + * are reserved for the second stage bootloader + */ + flash0: flash@10000100 { + compatible = "soc-nv-flash"; + label = "FLASH_RP2"; + + write-block-size = <1>; + }; + + clk_peri: uart-clock { + compatible = "fixed-clock"; + clock-frequency = <125000000>; + #clock-cells = <0>; + }; + + soc { + gpio0: gpio@40014000 { + compatible = "raspberrypi,rp2-gpio"; + reg = <0x40014000 DT_SIZE_K(4)>; + gpio-controller; + #gpio-cells = <2>; + label = "GPIO_0"; + status = "disabled"; + }; + + pwm0: pwm@40050000 { + compatible = "raspberrypi,rp2-pwm"; + reg = <0x40050000 DT_SIZE_K(4)>; + #pwm-cells = <2>; + label = "PWM_0"; + status = "disabled"; + }; + + uart0: uart@40034000 { + compatible = "raspberrypi,rp2-uart"; + reg = <0x40034000 DT_SIZE_K(4)>; + clocks = <&clk_peri>; + interrupts = <20 3>; + interrupt-names = "uart0"; + label = "UART_0"; + status = "disabled"; + }; + + uart1: uart@40038000 { + compatible = "raspberrypi,rp2-uart"; + reg = <0x40038000 DT_SIZE_K(4)>; + clocks = <&clk_peri>; + interrupts = <21 3>; + interrupt-names = "uart1"; + label = "UART_1"; + status = "disabled"; + }; + }; +}; + +&nvic { + arm,num-irq-priority-bits = <3>; +}; diff --git a/dts/bindings/gpio/raspberrypi,rp2-gpio.yaml b/dts/bindings/gpio/raspberrypi,rp2-gpio.yaml new file mode 100644 index 0000000000000..33fb95ef44ea6 --- /dev/null +++ b/dts/bindings/gpio/raspberrypi,rp2-gpio.yaml @@ -0,0 +1,22 @@ +# Copyright (c) 2021, Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +description: Raspberry Pi GPIO + +compatible: "raspberrypi,rp2-gpio" + +include: [gpio-controller.yaml, base.yaml] + +properties: + reg: + required: true + + label: + required: true + + "#gpio-cells": + const: 2 + +gpio-cells: + - pin + - flags diff --git a/dts/bindings/pwm/raspberrypi,rp2-pwm.yaml b/dts/bindings/pwm/raspberrypi,rp2-pwm.yaml new file mode 100644 index 0000000000000..e9fb406056068 --- /dev/null +++ b/dts/bindings/pwm/raspberrypi,rp2-pwm.yaml @@ -0,0 +1,26 @@ +# SPDX-License-Identifier: Apache-2.0 + +description: RASPBERRYPI PWM + +compatible: "raspberrypi,rp2-pwm" + +include: [pwm-controller.yaml, base.yaml] + +properties: + reg: + required: true + + label: + required: true + + prescaler: + type: int + required: true + description: Divider value used to divide the system clock(125MHz on rpi pico). + + "#pwm-cells": + const: 2 + +pwm-cells: + - channel + - flags diff --git a/dts/bindings/serial/raspberrypi,rp2-uart.yaml b/dts/bindings/serial/raspberrypi,rp2-uart.yaml new file mode 100644 index 0000000000000..4fdb4bc50f7d0 --- /dev/null +++ b/dts/bindings/serial/raspberrypi,rp2-uart.yaml @@ -0,0 +1,22 @@ +description: Raspberry Pi UART + +compatible: "raspberrypi,rp2-uart" + +include: uart-controller.yaml + +properties: + reg: + required: true + + interrupts: + required: true + + tx-pin: + type: int + required: true + description: TX pin as a GPIO number + + rx-pin: + type: int + required: true + description: RX pin as a GPIO number diff --git a/modules/Kconfig b/modules/Kconfig index 32821908aecb3..b5826081a1224 100644 --- a/modules/Kconfig +++ b/modules/Kconfig @@ -23,6 +23,7 @@ source "modules/Kconfig.mcux" source "modules/Kconfig.microchip" source "modules/Kconfig.nuvoton" source "modules/Kconfig.open-amp" +source "modules/Kconfig.raspberrypi" source "modules/Kconfig.silabs" source "modules/Kconfig.simplelink" source "modules/Kconfig.sof" diff --git a/modules/Kconfig.raspberrypi b/modules/Kconfig.raspberrypi new file mode 100644 index 0000000000000..948cd0d98d990 --- /dev/null +++ b/modules/Kconfig.raspberrypi @@ -0,0 +1,5 @@ +# Copyright (c) 2021 Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +config HAS_RASPBERRYPI + bool diff --git a/soc/arm/raspberrypi/CMakeLists.txt b/soc/arm/raspberrypi/CMakeLists.txt new file mode 100644 index 0000000000000..226f3bd626f61 --- /dev/null +++ b/soc/arm/raspberrypi/CMakeLists.txt @@ -0,0 +1,3 @@ +# SPDX-License-Identifier: Apache-2.0 + +add_subdirectory(${SOC_SERIES}) diff --git a/soc/arm/raspberrypi/Kconfig b/soc/arm/raspberrypi/Kconfig new file mode 100644 index 0000000000000..8bbb37b14a99d --- /dev/null +++ b/soc/arm/raspberrypi/Kconfig @@ -0,0 +1,17 @@ +# Raspberry Pi (RP) MCU line + +# Copyright (c) 2021 Nordic Semiconductor ASA +# Copyright (c) 2021 Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +config SOC_FAMILY_RASPBERRY_PI + bool + +if SOC_FAMILY_RASPBERRY_PI +config SOC_FAMILY + string + default "raspberrypi" + +source "soc/arm/raspberrypi/*/Kconfig.soc" + +endif # SOC_FAMILY_RASPBERRY_PI diff --git a/soc/arm/raspberrypi/Kconfig.defconfig b/soc/arm/raspberrypi/Kconfig.defconfig new file mode 100644 index 0000000000000..50b6926067ac3 --- /dev/null +++ b/soc/arm/raspberrypi/Kconfig.defconfig @@ -0,0 +1,10 @@ +# Raspberry Pi (RP) MCU line + +# Copyright (c) 2021 Nordic Semiconductor ASA +# SPDX-License-Identifier: Apache-2.0 + +if SOC_FAMILY_RASPBERRY_PI + +source "soc/arm/raspberrypi/*/Kconfig.defconfig.series" + +endif # SOC_FAMILY_RASPBERRY_PI diff --git a/soc/arm/raspberrypi/Kconfig.soc b/soc/arm/raspberrypi/Kconfig.soc new file mode 100644 index 0000000000000..a45653f93fc9d --- /dev/null +++ b/soc/arm/raspberrypi/Kconfig.soc @@ -0,0 +1,6 @@ +# Raspberry Pi (RP) MCU line + +# Copyright (c) 2021 Nordic Semiconductor ASA +# SPDX-License-Identifier: Apache-2.0 + +source "soc/arm/raspberrypi/*/Kconfig.series" diff --git a/soc/arm/raspberrypi/rp2/CMakeLists.txt b/soc/arm/raspberrypi/rp2/CMakeLists.txt new file mode 100644 index 0000000000000..02720459b61c0 --- /dev/null +++ b/soc/arm/raspberrypi/rp2/CMakeLists.txt @@ -0,0 +1,14 @@ +# Copyright (c) 2021 Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +zephyr_library() + +zephyr_library_sources( + soc.c + rp2_init.c + ) + +zephyr_library_include_directories( + ${ZEPHYR_BASE}/kernel/include + ${ZEPHYR_BASE}/arch/arm/include + ) diff --git a/soc/arm/raspberrypi/rp2/Kconfig.defconfig.rp2040 b/soc/arm/raspberrypi/rp2/Kconfig.defconfig.rp2040 new file mode 100644 index 0000000000000..a410181900c62 --- /dev/null +++ b/soc/arm/raspberrypi/rp2/Kconfig.defconfig.rp2040 @@ -0,0 +1,8 @@ +# # Raspberry Pi RP2040 MCU + +# Copyright (c) 2021 Nordic Semiconductor ASA +# SPDX-License-Identifier: Apache-2.0 + +config SOC + default "rp2040" + depends on SOC_RP2040 diff --git a/soc/arm/raspberrypi/rp2/Kconfig.defconfig.series b/soc/arm/raspberrypi/rp2/Kconfig.defconfig.series new file mode 100644 index 0000000000000..a7ff5d7826477 --- /dev/null +++ b/soc/arm/raspberrypi/rp2/Kconfig.defconfig.series @@ -0,0 +1,53 @@ +# Raspberry Pi RP20XX MCU line + +# Copyright (c) 2021 Nordic Semiconductor ASA +# Copyright (c) 2021 Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +if SOC_SERIES_RP2XXX + +source "soc/arm/raspberrypi/rp2/Kconfig.defconfig.rp2*" + +config SOC_SERIES + default "rp2" + +config NUM_IRQS + default 26 + +choice + prompt "Raspberry Pi flash type" + +config RP2_FLASH_W25Q080 + bool "W25Q080" + +config RP2_FLASH_GENERIC_03H + bool "Generic 03H" + +config RP2_FLASH_IS25LP080 + bool "IS25LP080" + +config RP2_FLASH_W25X10CL + bool "W25X10CL" + +endchoice + +config RP2_FLASH_BOOT_FILE + string + default "boot2_w25q080.S" if RP2_FLASH_W25Q080 + default "boot2_generic_03h.S" if RP2_FLASH_GENERIC_03H + default "boot2_is25lp080.S" if RP2_FLASH_IS25LP080 + default "boot2_w25x10cl.S" if RP2_FLASH_W25X10CL + +config UART_RASPBERRYPI + default y + depends on SERIAL + +config GPIO_RASPBERRYPI + default y + depends on GPIO + +config PWM_RASPBERRYPI + default y + depends on PWM + +endif # SOC_SERIES_RP2XXX diff --git a/soc/arm/raspberrypi/rp2/Kconfig.series b/soc/arm/raspberrypi/rp2/Kconfig.series new file mode 100644 index 0000000000000..3e2701bd59f81 --- /dev/null +++ b/soc/arm/raspberrypi/rp2/Kconfig.series @@ -0,0 +1,18 @@ +# Raspberry Pi RP2XXX MCU line + +# Copyright (c) 2021 Nordic Semiconductor ASA +# Copyright (c) 2021 Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +config SOC_SERIES_RP2XXX + bool "Raspberry Pi RP2 series MCU" + select ARM + select CPU_CORTEX_M0PLUS + select CPU_CORTEX_M_HAS_SYSTICK + select CPU_CORTEX_M_HAS_VTOR + select CPU_HAS_ARM_MPU + select SOC_FAMILY_RASPBERRY_PI + select HAS_RASPBERRYPI + select XIP + help + Enable support for Raspberry Pi RP20 MCU series diff --git a/soc/arm/raspberrypi/rp2/Kconfig.soc b/soc/arm/raspberrypi/rp2/Kconfig.soc new file mode 100644 index 0000000000000..4b1dccbbd1bf8 --- /dev/null +++ b/soc/arm/raspberrypi/rp2/Kconfig.soc @@ -0,0 +1,14 @@ +# Raspberry Pi RP2XXX MCU line + +# Copyright (c) 2021 Nordic Semiconductor ASA +# Copyright (c) 2021 Yonatan Schachter +# SPDX-License-Identifier: Apache-2.0 + +choice + prompt "RP2xxx MCU Selection" + depends on SOC_SERIES_RP2XXX + +config SOC_RP2040 + bool "Raspberry Pi RP2040" + +endchoice diff --git a/soc/arm/raspberrypi/rp2/linker.ld b/soc/arm/raspberrypi/rp2/linker.ld new file mode 100644 index 0000000000000..c1755ea1c4c4b --- /dev/null +++ b/soc/arm/raspberrypi/rp2/linker.ld @@ -0,0 +1,22 @@ +/* linker.ld - Linker command/script file */ + +/* + * Copyright (c) 2014 Wind River Systems, Inc. + * Copyright (c) 2021 Yonatan Schachter + * + * SPDX-License-Identifier: Apache-2.0 + */ +MEMORY +{ + BOOT_FLASH (r) : ORIGIN = 0x10000000, LENGTH = 256 +} + +#include + +SECTIONS +{ + SECTION_PROLOGUE(BOOT_FLASH,, SUBALIGN(4)) + { + KEEP(*(.boot2)) + } +} diff --git a/soc/arm/raspberrypi/rp2/rp2_init.c b/soc/arm/raspberrypi/rp2/rp2_init.c new file mode 100644 index 0000000000000..6f4cafab38558 --- /dev/null +++ b/soc/arm/raspberrypi/rp2/rp2_init.c @@ -0,0 +1,38 @@ +/* + * Copyright (c) 2021 Yonatan Schachter + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include "pico.h" + +#include "hardware/regs/m0plus.h" +#include "hardware/regs/resets.h" +#include "hardware/structs/mpu.h" +#include "hardware/structs/scb.h" +#include "hardware/structs/padsbank0.h" + +#include "hardware/clocks.h" +#include "hardware/irq.h" +#include "hardware/resets.h" + +void rp2_init(void) +{ + reset_block(~(RESETS_RESET_IO_QSPI_BITS | + RESETS_RESET_PADS_QSPI_BITS | + RESETS_RESET_PLL_USB_BITS | + RESETS_RESET_PLL_SYS_BITS)); + + unreset_block_wait(RESETS_RESET_BITS & ~( + RESETS_RESET_ADC_BITS | + RESETS_RESET_RTC_BITS | + RESETS_RESET_SPI0_BITS | + RESETS_RESET_SPI1_BITS | + RESETS_RESET_UART0_BITS | + RESETS_RESET_UART1_BITS | + RESETS_RESET_USBCTRL_BITS)); + + clocks_init(); + + unreset_block_wait(RESETS_RESET_BITS); +} diff --git a/soc/arm/raspberrypi/rp2/soc.c b/soc/arm/raspberrypi/rp2/soc.c new file mode 100644 index 0000000000000..d3f0199de9c5c --- /dev/null +++ b/soc/arm/raspberrypi/rp2/soc.c @@ -0,0 +1,53 @@ +/* + * Copyright (c) 2021 Nordic Semiconductor ASA + * Copyright (c) 2021 Yonatan Schachter + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/** + * @file + * @brief System/hardware module for Raspberry Pi RP2040 family processor + * + * This module provides routines to initialize and support board-level hardware + * for the Raspberry Pi RP2040 family processor. + */ + +#include +#include +#include + + +#ifdef CONFIG_RUNTIME_NMI +extern void z_arm_nmi_init(void); +#define NMI_INIT() z_arm_nmi_init() +#else +#define NMI_INIT() +#endif + +#define LOG_LEVEL CONFIG_SOC_LOG_LEVEL +LOG_MODULE_REGISTER(soc); + +void rp2_init(void); + +static int raspberry_pi_rp2040_init(const struct device *arg) +{ + uint32_t key; + + rp2_init(); + + ARG_UNUSED(arg); + + key = irq_lock(); + + /* Install default handler that simply resets the CPU + * if configured in the kernel, NOP otherwise + */ + NMI_INIT(); + + irq_unlock(key); + + return 0; +} + +SYS_INIT(raspberry_pi_rp2040_init, PRE_KERNEL_1, 0); diff --git a/soc/arm/raspberrypi/rp2/soc.h b/soc/arm/raspberrypi/rp2/soc.h new file mode 100644 index 0000000000000..c4334bd351ceb --- /dev/null +++ b/soc/arm/raspberrypi/rp2/soc.h @@ -0,0 +1,18 @@ +/* + * Copyright (c) 2016 Linaro Limited + * Copyright (c) 2021 Yonatan Schachter + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/** + * @file SoC configuration macros for the Raspberry Pi RP2040 family processors + */ + +#ifndef _RASPBERRY_PI_RP2040_SOC_H_ +#define _RASPBERRY_PI_RP2040_SOC_H_ + +#define __VTOR_PRESENT 1 +#define __MPU_PRESENT 1 + +#endif /* _RASPBERRY_PI_RP2040_SOC_H_ */ diff --git a/west.yml b/west.yml index e8b272791d1ac..df91356a97f7e 100644 --- a/west.yml +++ b/west.yml @@ -142,6 +142,9 @@ manifest: - name: trusted-firmware-m path: modules/tee/tfm revision: 51cdecd6f9e6b0aa66da45db22f4b478183d472f + - name: hal_raspberrypi + path: modules/hal/raspberrypi + revision: pull/1/head - name: tfm-mcuboot # This is used by the trusted-firmware-m module. repo-path: mcuboot path: modules/tee/tfm-mcuboot