diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
index ae6f9f83287576d61f084f70737feed34161dcb0..c366e6206e52b395aa7ea58f514c776ac4745107 100644
--- a/arch/arm/Kconfig
+++ b/arch/arm/Kconfig
@@ -20,7 +20,7 @@ config CPU_CORTEX
 
 config ARM_CUSTOM_INTERRUPT_CONTROLLER
 	bool
-	depends on !CPU_CORTEX_M
+	depends on !CPU_CORTEX_M || SOC_BCM2837
 	help
 	  This option indicates that the ARM CPU is connected to a custom (i.e.
 	  non-GIC) interrupt controller.
diff --git a/arch/arm/core/aarch64/Kconfig b/arch/arm/core/aarch64/Kconfig
index b5494b455c038b0b2a5411daee6dea4456915fc8..aac7867222fa253b4cb15995300c2f9dce4e95ca 100644
--- a/arch/arm/core/aarch64/Kconfig
+++ b/arch/arm/core/aarch64/Kconfig
@@ -9,7 +9,6 @@ config CPU_CORTEX_A
 	select HAS_FLASH_LOAD_OFFSET
 	select USE_SWITCH
 	select USE_SWITCH_SUPPORTED
-	select SCHED_IPI_SUPPORTED if SMP
 	help
 	  This option signifies the use of a CPU of the Cortex-A family.
 
diff --git a/arch/arm/core/aarch64/smp.c b/arch/arm/core/aarch64/smp.c
index 2735be6cc05c5ec86139b7e88da8581eccafd4af..5030cd02cdac6b2e5891f91abfbeb02e2b0d5526 100644
--- a/arch/arm/core/aarch64/smp.c
+++ b/arch/arm/core/aarch64/smp.c
@@ -35,6 +35,18 @@ volatile uint32_t arm64_cpu_up_flag;
  */
 volatile _cpu_t *_curr_cpu[CONFIG_MP_NUM_CPUS];
 
+#ifdef CONFIG_SOC_BCM2837
+static ALWAYS_INLINE void __SEV(void)
+{
+	__asm__ volatile ("sev" : : : "memory");
+}
+
+static void sys_write64(uint64_t val, uintptr_t addr) {
+	sys_write32(val, addr);
+	sys_write32(val >> 32, addr + sizeof(uint32_t));
+}
+#endif
+
 extern void __start(void);
 /* Called from Zephyr initialization */
 void arch_start_cpu(int cpu_num, k_thread_stack_t *stack, int sz,
@@ -52,10 +64,16 @@ void arch_start_cpu(int cpu_num, k_thread_stack_t *stack, int sz,
 	arm64_cpu_up_flag = cpu_num;
 	arch_dcache_flush((void *)&arm64_cpu_up_flag, sizeof(uint32_t));
 
+#ifdef CONFIG_SOC_BCM2837
+	sys_write64((uint64_t) &__start, 0xd8 + 0x8 * cpu_num);
+	__DSB();
+	__SEV();
+#else
 	/* TODO: get mpidr from device tree, using cpu_num */
 	err = psci_cpu_on(cpu_num, (uint64_t)&__start);
 	if (err)
 		printk("Failed to boot CPU%d (%d)\n", cpu_num, err);
+#endif
 
 	while (arm64_cpu_up_flag != 0) {
 		;
@@ -71,9 +89,11 @@ void z_arm64_secondary_start(void)
 
 	arm_mmu_init(NULL);
 
+#ifndef CONFIG_SOC_BCM2837
 	arm_gic_secondary_init();
 
 	irq_enable(0);
+#endif
 
 	arm64_cpu_up_flag = 0;
 
@@ -83,6 +103,7 @@ void z_arm64_secondary_start(void)
 }
 
 #ifdef CONFIG_SMP
+#ifndef CONFIG_SOC_BCM2837
 
 void sched_ipi_handler(const void *unused)
 {
@@ -114,3 +135,4 @@ static int arm64_smp_init(const struct device *dev)
 
 SYS_INIT(arm64_smp_init, PRE_KERNEL_1, CONFIG_KERNEL_INIT_PRIORITY_DEFAULT);
 #endif
+#endif
diff --git a/arch/arm/include/aarch64/exc.h b/arch/arm/include/aarch64/exc.h
index 937ef6bfb43153ae818988593257162943026b02..5d07cfc86f29adcd79e9b44913f99c9242387ac6 100644
--- a/arch/arm/include/aarch64/exc.h
+++ b/arch/arm/include/aarch64/exc.h
@@ -34,7 +34,7 @@ extern void z_arm64_offload(void);
 
 static ALWAYS_INLINE bool arch_is_in_isr(void)
 {
-	return _kernel.cpus[0].nested != 0U;
+	return arch_curr_cpu()->nested != 0U;
 }
 
 
diff --git a/boards/arm/raspi3/Kconfig.board b/boards/arm/raspi3/Kconfig.board
new file mode 100644
index 0000000000000000000000000000000000000000..e15f9d03c8e6534a1fd40372045f56b014720f89
--- /dev/null
+++ b/boards/arm/raspi3/Kconfig.board
@@ -0,0 +1,8 @@
+# Copyright (c) 2019 Carlo Caione <ccaione@baylibre.com>
+# SPDX-License-Identifier: Apache-2.0
+
+config BOARD_RASPI3
+	bool "Raspberry Pi 3 Model B+ and QEMU Machine raspi3"
+	depends on SOC_BCM2837
+	select ARM64
+	select QEMU_TARGET
diff --git a/boards/arm/raspi3/Kconfig.defconfig b/boards/arm/raspi3/Kconfig.defconfig
new file mode 100644
index 0000000000000000000000000000000000000000..90c9ba689cc6b72b69d6fddd4d1e43c810730c8b
--- /dev/null
+++ b/boards/arm/raspi3/Kconfig.defconfig
@@ -0,0 +1,12 @@
+# Copyright (c) 2019 Carlo Caione <ccaione@baylibre.com>
+# SPDX-License-Identifier: Apache-2.0
+
+if BOARD_RASPI3
+
+config BUILD_OUTPUT_BIN
+	default y
+
+config BOARD
+	default "raspi3"
+
+endif # BOARD_RASPI3
diff --git a/boards/arm/raspi3/board.cmake b/boards/arm/raspi3/board.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..68c4452cab15ce0bf8655332bc91c5e0e5b8b434
--- /dev/null
+++ b/boards/arm/raspi3/board.cmake
@@ -0,0 +1,17 @@
+# Copyright (c) 2019 Carlo Caione <ccaione@baylibre.com>
+# SPDX-License-Identifier: Apache-2.0
+
+set(EMU_PLATFORM qemu)
+set(QEMU_ARCH aarch64)
+set(QEMU_KERNEL_OPTION "-kernel;${ZEPHYR_BINARY_DIR}/zephyr.bin")
+
+# https://github.com/s-matyukevich/raspberry-pi-os/issues/8#issuecomment-411024746
+set(QEMU_FLAGS_${ARCH}
+  -M raspi3
+  -smp 4
+  -nographic
+  -no-reboot
+  # To see Mini UART on qemu's stdout (default is PL011):
+  # -serial null -serial chardev:con -monitor none
+  )
+board_set_debugger_ifnset(qemu)
diff --git a/boards/arm/raspi3/raspi3.dts b/boards/arm/raspi3/raspi3.dts
new file mode 100644
index 0000000000000000000000000000000000000000..3696627252fb31e6c43f7bec1d0d09f733d9dc53
--- /dev/null
+++ b/boards/arm/raspi3/raspi3.dts
@@ -0,0 +1,139 @@
+/*
+* Copyright (c) 2019 Carlo Caione <ccaione@baylibre.com>
+*
+* SPDX-License-Identifier: Apache-2.0
+*
+*/
+
+/dts-v1/;
+
+#include <mem.h>
+#include <arm/armv8-a.dtsi>
+
+/ {
+	interrupt-parent = <&intc>;
+
+	cpus {
+		#address-cells = <1>;
+		#size-cells = <0>;
+
+		cpu@0 {
+			device_type = "cpu";
+			compatible = "arm,cortex-a53";
+			reg = <0>;
+		};
+
+		cpu@1 {
+			device_type = "cpu";
+			compatible = "arm,cortex-a53";
+			reg = <1>;
+		};
+
+		cpu@2 {
+			device_type = "cpu";
+			compatible = "arm,cortex-a53";
+			reg = <2>;
+		};
+
+		cpu@3 {
+			device_type = "cpu";
+			compatible = "arm,cortex-a53";
+			reg = <3>;
+		};
+	};
+
+	uartclk: apb-pclk {
+		compatible = "fixed-clock";
+		/* BUG: This is not used, instead the parameters are hardcored in uart_pl011. */
+		clock-frequency = <14000000>;
+		#clock-cells = <0>;
+	};
+
+	soc {
+		/* https://github.com/s-matyukevich/raspberry-pi-os/blob/master/docs/lesson03/rpi-os.md#configuring-interrupt-controller */
+		intc: interrupt-controller@3f00b200 {
+			compatible = "brcm,bcm2835-armctrl-ic";
+			reg = <0x3f00b200 0x200>;
+			interrupt-controller;
+			#interrupt-cells = <3>;
+			label = "intc";
+		};
+
+		local_intc: local_intc@40000000 {
+			compatible = "brcm,bcm2835-l1-intc";
+			reg = <0x40000000 0x100>;
+			interrupt-controller;
+			#interrupt-cells = <3>;
+			label = "l1-intc";
+		};
+
+		timer {
+			compatible = "arm,arm-timer";
+			interrupt-parent = <&local_intc>;
+			/* TODO: Is the intc nested into the local_intc? Maybe we can tell zephyr to generate the unique interrupt number for us? */
+			interrupts = <72 0 0>, <73 0 0>, <75 0 0>, <74 0 0>; /* CNTPSIRQ, CNTPNSIRQ, CNTVIRQ, CNTHPIRQ */
+			label = "arch_timer";
+		};
+
+		/* https://github.com/s-matyukevich/raspberry-pi-os/blob/master/docs/lesson03/rpi-os.md#timer-initialization */
+		timer@3f003000 {
+			compatible = "brcm,bcm2835-system-timer";
+			reg = <0x3f003000 0x20>;
+			interrupts = <0 0 0>, <1 0 0>, <2 0 0>, <3 0 0>;
+			/* This could be a reference to BCM2835_CLOCK_TIMER,
+			* but we don't have the driver using the common clock
+			* support yet.
+			*/
+			clock-frequency = <1000000>; /* 1MHz */
+		};
+
+		/* Page 196 in the "BCM2837 ARM Peripherals manual" https://github.com/raspberrypi/documentation/files/1888662/BCM2837-ARM-Peripherals.-.Revised.-.V2-1.pdf */
+		/* TODO: This is likely not required. We just need timer@3f003000 for the system clock and armv7-timer for the timer ticks. */
+		timer@3f00b000 {
+			compatible = "brcm,bcm2835-arm-timer";
+			reg = <0x3f00b000 0x1000>;
+			interrupts = <64 0 0>;
+			clock-frequency = <1000000>; /* 1MHz */
+		};
+
+		uart0: uart@3f201000 {
+			compatible = "arm,pl011";
+			/* #clock-cells = <1>; */
+			reg = <0x3f201000 0x1000>;
+			status = "disabled";
+			interrupts = <57 0 0>;
+			interrupt-names = "irq_0";
+			clocks = <&uartclk>;
+			label = "UART_0";
+		};
+
+		/* sram: memory@80000 { */
+			/* device_type = "memory"; */
+			/* compatible = "mmio-sram"; */
+			/* BCM2837 has 1GiB of RAM. */
+
+			/* 0x80000 is the memory offset to which the kerenl image is loaded by the bootloader. */
+			/* If this is wrong, references to static data in the kernel image are off. */
+			/* https://wiki.osdev.org/Raspberry_Pi_Bare_Bones#Pi_3.2C_4 */
+			/* reg = <0x80000 1024>; */
+			/* label = "sram"; */
+		/* }; */
+	};
+};
+
+/ {
+	model = "Raspberry Pi 3 Model B+";
+	compatible = "qemu,arm-cortex-a53";
+
+	chosen {
+		zephyr,console = &uart0;
+		zephyr,shell-uart = &uart0;
+		/* TODO: why has this no effect? falls back to size 0xffffffffffff6000 */
+		/* zephyr,sram = &sram; */
+	};
+};
+
+&uart0 {
+	status = "okay";
+	current-speed = <115200>;
+};
diff --git a/boards/arm/raspi3/raspi3.yaml b/boards/arm/raspi3/raspi3.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..eda12d153090a5bb29d72649753339a81971f22c
--- /dev/null
+++ b/boards/arm/raspi3/raspi3.yaml
@@ -0,0 +1,14 @@
+identifier: raspi3
+name: Raspberry Pi 3
+type: qemu
+simulation: qemu
+arch: arm
+toolchain:
+  - zephyr
+  - cross-compile
+ram: 256
+testing:
+  default: true
+  ignore_tags:
+    - net
+    - bluetooth
diff --git a/boards/arm/raspi3/raspi3_defconfig b/boards/arm/raspi3/raspi3_defconfig
new file mode 100644
index 0000000000000000000000000000000000000000..70722f07f6509608a68a77e5854bd3a0d278d989
--- /dev/null
+++ b/boards/arm/raspi3/raspi3_defconfig
@@ -0,0 +1,47 @@
+CONFIG_SOC_BCM2837=y
+CONFIG_BOARD_RASPI3=y
+CONFIG_XIP=n
+
+# QEMU settings
+
+# Memory offset to which the kerenl image is loaded by the bootloader.
+# If this is wrong, references to static data in the kernel image are off.
+# https://wiki.osdev.org/Raspberry_Pi_Bare_Bones#Pi_3.2C_4
+CONFIG_SRAM_BASE_ADDRESS=0x80000
+# In KiB.
+CONFIG_SRAM_SIZE=256
+
+# Enable UART driver
+CONFIG_SERIAL=y
+
+# Enable console
+CONFIG_CONSOLE=y
+CONFIG_UART_CONSOLE=y
+
+# Enable serial port
+CONFIG_UART_PL011=y
+CONFIG_UART_PL011_PORT0=y
+CONFIG_UART_INTERRUPT_DRIVEN=y
+
+CONFIG_QEMU_ICOUNT=n
+
+CONFIG_LOG=y
+CONFIG_LOG_MINIMAL=y
+
+CONFIG_ARM_ARCH_TIMER=y
+
+CONFIG_SMP=y
+CONFIG_MP_NUM_CPUS=4
+
+CONFIG_CACHE_FLUSHING=y
+CONFIG_TIMEOUT_64BIT=y
+CONFIG_ARMV8_A_NS=y
+
+CONFIG_DEBUG=y
+CONFIG_ASSERT=y
+CONFIG_ASSERT_VERBOSE=y
+CONFIG_STACK_SENTINEL=y
+CONFIG_INIT_STACKS=y
+
+CONFIG_TICKLESS_KERNEL=n
+CONFIG_LOG_PRINTK=n
diff --git a/drivers/serial/uart_pl011.c b/drivers/serial/uart_pl011.c
index cd9a975c090470cc9ab80b1eb89e7b0cf747a1a3..b3c7c2b0e765f66c90b2caa7858d4de6e77e30a8 100644
--- a/drivers/serial/uart_pl011.c
+++ b/drivers/serial/uart_pl011.c
@@ -183,8 +183,13 @@ static int pl011_set_baudrate(const struct device *dev,
 		return -EINVAL;
 	}
 
+#ifdef CONFIG_BOARD_RASPI3
+	PL011_REGS(dev)->ibrd = 26;
+	PL011_REGS(dev)->fbrd = 3;
+#else
 	PL011_REGS(dev)->ibrd = bauddiv >> PL011_FBRD_WIDTH;
 	PL011_REGS(dev)->fbrd = bauddiv & ((1u << PL011_FBRD_WIDTH) - 1u);
+#endif
 
 	__DMB();
 
@@ -351,11 +356,51 @@ static const struct uart_driver_api pl011_driver_api = {
 #endif /* CONFIG_UART_INTERRUPT_DRIVEN */
 };
 
+#ifdef CONFIG_BOARD_RASPI3
+#define PBASE 0x3F000000
+
+#define GPFSEL1 (PBASE + 0x00200004)
+#define GPSET0 (PBASE + 0x0020001C)
+#define GPCLR0 (PBASE + 0x00200028)
+#define GPPUD (PBASE + 0x00200094)
+#define GPPUDCLK0 (PBASE + 0x00200098)
+
+static void write32_sys(uintptr_t addr, uint32_t val) {
+	sys_write32(val, addr);
+}
+
+#define GPIO_ALT0 4 // UART0/PL011
+#define GPIO_ALT5 2 // UART1/Mini/AUX
+
+static void raspi3_gpio_enable_pl011(void)
+{
+	unsigned int selector;  // 32 bits
+
+	selector = sys_read32(GPFSEL1);
+	selector &= ~(7 << 12);
+	selector |= GPIO_ALT0 << 12; // Set GPIO14
+	selector &= ~(7 << 15);
+	selector |= GPIO_ALT0 << 15; // Set GPIO15
+	write32_sys(GPFSEL1, selector);
+
+	// Set GPIO pull-up/down. Common to Mini UART (AUX) and PL011.
+	write32_sys(GPPUD, 0);
+	k_busy_wait(150); 	/* 150 cycles ~= 150us */
+	write32_sys(GPPUDCLK0, (1 << 14) | (1 << 15));
+	k_busy_wait(150);
+	write32_sys(GPPUDCLK0, 0);
+}
+#endif
+
 static int pl011_init(const struct device *dev)
 {
 	int ret;
 	uint32_t lcrh;
 
+#ifdef CONFIG_BOARD_RASPI3
+	raspi3_gpio_enable_pl011();
+#endif
+
 	/* disable the uart */
 	pl011_disable(dev);
 	pl011_disable_fifo(dev);
diff --git a/drivers/timer/Kconfig b/drivers/timer/Kconfig
index 4233b9d7131c771e305854635cc09287206c60a1..5a33674fc43c097245dcae1b1e2a94ebb2e66287 100644
--- a/drivers/timer/Kconfig
+++ b/drivers/timer/Kconfig
@@ -113,7 +113,6 @@ config ARCV2_TIMER_IRQ_PRIORITY
 
 config ARM_ARCH_TIMER
 	bool "ARM architected timer"
-	depends on GIC
 	select ARCH_HAS_CUSTOM_BUSY_WAIT
 	select TICKLESS_CAPABLE
 	help
diff --git a/dts/bindings/interrupt-controller/brcm,bcm2835-armctrl-ic.yaml b/dts/bindings/interrupt-controller/brcm,bcm2835-armctrl-ic.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..93386a80ec19df90323fc7331560862041686e9f
--- /dev/null
+++ b/dts/bindings/interrupt-controller/brcm,bcm2835-armctrl-ic.yaml
@@ -0,0 +1,21 @@
+# Copyright (c) 2018 Marvell
+# SPDX-License-Identifier: Apache-2.0
+
+description: Interrupt Controller
+
+compatible: "brcm,bcm2835-armctrl-ic"
+
+include: base.yaml
+
+properties:
+    reg:
+      required: true
+
+    label:
+      required: true
+
+# GIC-compatible to allow reuse of arm,arm-timer. flags and priority are always 0.
+interrupt-cells:
+  - irq
+  - flags
+  - priority
diff --git a/dts/bindings/interrupt-controller/brcm,bcm2835-l1-intc.yaml b/dts/bindings/interrupt-controller/brcm,bcm2835-l1-intc.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..917b981413662d8f274342a93db585749a91da9c
--- /dev/null
+++ b/dts/bindings/interrupt-controller/brcm,bcm2835-l1-intc.yaml
@@ -0,0 +1,21 @@
+# Copyright (c) 2018 Marvell
+# SPDX-License-Identifier: Apache-2.0
+
+description: Interrupt Controller
+
+compatible: "brcm,bcm2835-l1-intc"
+
+include: base.yaml
+
+properties:
+    reg:
+      required: true
+
+    label:
+      required: true
+
+# GIC-compatible to allow reuse of arm,arm-timer. flags and priority are always 0.
+interrupt-cells:
+  - irq
+  - flags
+  - priority
diff --git a/dts/bindings/serial/arm,raspi3.yaml b/dts/bindings/serial/arm,raspi3.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..f1731792e479dd1d6b3bd2ee85d4712bb947ee9a
--- /dev/null
+++ b/dts/bindings/serial/arm,raspi3.yaml
@@ -0,0 +1,9 @@
+description: raspi3 UART
+
+compatible: "arm,raspi3"
+
+include: uart-controller.yaml
+
+properties:
+    reg:
+      required: true
diff --git a/include/arch/arm/aarch64/scripts/linker.ld b/include/arch/arm/aarch64/scripts/linker.ld
index 01b7d6b7206a277d54803c3f3d735030017c9aa9..8c3b317cfb041c19bd84c72e243e06860de713c0 100644
--- a/include/arch/arm/aarch64/scripts/linker.ld
+++ b/include/arch/arm/aarch64/scripts/linker.ld
@@ -111,6 +111,12 @@ SECTIONS
     {
         _image_text_start = .;
 
+        /* This has to be the first entry to allow __start to be located at
+         * 0x80000 on the Raspberry Pi 3b. */
+        *(.text)
+        *(".text.*")
+        *(.gnu.linkonce.t.*)
+
         _vector_start = .;
         KEEP(*(.exc_vector_table))
         KEEP(*(".exc_vector_table.*"))
@@ -119,10 +125,6 @@ SECTIONS
 
         _vector_end = .;
 
-        *(.text)
-        *(".text.*")
-        *(.gnu.linkonce.t.*)
-
         /*
          * These are here according to 'arm-zephyr-elf-ld --verbose',
          * after .gnu.linkonce.t.*
diff --git a/soc/arm/bcm2837/CMakeLists.txt b/soc/arm/bcm2837/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..584f43dab059861d6e234012098733b0ab5b5e0a
--- /dev/null
+++ b/soc/arm/bcm2837/CMakeLists.txt
@@ -0,0 +1,7 @@
+# Copyright (c) 2019 Carlo Caione <ccaione@baylibre.com>
+# SPDX-License-Identifier: Apache-2.0
+
+zephyr_library_sources_ifdef(CONFIG_ARM_MMU mmu_regions.c)
+
+zephyr_sources_ifdef(CONFIG_SOC_BCM2837    plat_core.S)
+zephyr_sources_ifdef(CONFIG_SOC_BCM2837    intc_bcm2837.c)
diff --git a/soc/arm/bcm2837/Kconfig.defconfig b/soc/arm/bcm2837/Kconfig.defconfig
new file mode 100644
index 0000000000000000000000000000000000000000..801c488d498e2e6eceb0e170116e171dcc54017c
--- /dev/null
+++ b/soc/arm/bcm2837/Kconfig.defconfig
@@ -0,0 +1,30 @@
+# Copyright (c) 2019 Carlo Caione <ccaione@baylibre.com>
+# SPDX-License-Identifier: Apache-2.0
+
+if SOC_BCM2837
+
+config SOC
+	default "bcm2837"
+
+config NUM_IRQS
+	# must be >= the highest interrupt number used
+	# - include the UART interrupts
+    # via BCM2837-PM Page 113
+	default 128
+
+config SYS_CLOCK_HW_CYCLES_PER_SEC
+	default 62500000
+
+# Workaround for not being able to have commas in macro arguments
+DT_CHOSEN_Z_FLASH := zephyr,flash
+
+config FLASH_SIZE
+	default $(dt_chosen_reg_size_int,$(DT_CHOSEN_Z_FLASH),0,K)
+
+config FLASH_BASE_ADDRESS
+	default $(dt_chosen_reg_addr_hex,$(DT_CHOSEN_Z_FLASH))
+
+config ARM_CUSTOM_INTERRUPT_CONTROLLER
+    default y
+
+endif # SOC_BCM2837
diff --git a/soc/arm/bcm2837/Kconfig.soc b/soc/arm/bcm2837/Kconfig.soc
new file mode 100644
index 0000000000000000000000000000000000000000..a5a92e4766464bbca765441363e1613ae10f7789
--- /dev/null
+++ b/soc/arm/bcm2837/Kconfig.soc
@@ -0,0 +1,7 @@
+# Copyright (c) 2019 Carlo Caione <ccaione@baylibre.com>
+# SPDX-License-Identifier: Apache-2.0
+
+config SOC_BCM2837
+	bool "BCM2837 and BCM2837B0 SoC, QEMU virt platform (raspi3)"
+	select ARM
+	select CPU_CORTEX_A53
diff --git a/soc/arm/bcm2837/README.md b/soc/arm/bcm2837/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..135a4cdd1ef6f801d2d9d9deb94eef94787886b8
--- /dev/null
+++ b/soc/arm/bcm2837/README.md
@@ -0,0 +1,9 @@
+# BCM2837
+
+SoC of the Raspberry Pi
+- 2 Mod. B v1.2,
+- 3 Mod. A+ (assumed to be qemu's `-M raspi3`)
+- 3 Mod. B
+- 3 Mod. B+.
+
+Peripheral Manual (BCM2837-PM): https://github.com/raspberrypi/documentation/files/1888662/BCM2837-ARM-Peripherals.-.Revised.-.V2-1.pdf
diff --git a/soc/arm/bcm2837/intc_bcm2837.c b/soc/arm/bcm2837/intc_bcm2837.c
new file mode 100644
index 0000000000000000000000000000000000000000..bbdc40fe3cd70044d06455714180d06f5cf76080
--- /dev/null
+++ b/soc/arm/bcm2837/intc_bcm2837.c
@@ -0,0 +1,207 @@
+/*
+ * Copyright 2020 Broadcom
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#include <sys/__assert.h>
+#include <arch/arm/aarch64/irq.h>
+
+/* TODO: Get these from device tree. */
+#define PBASE 0x3f000000
+#define BCM2836_ARMCTRL_BASE (PBASE+0x0000B200)
+
+/* Definitions copied from linux's irq-bcm2835.c: */
+
+/* Put the bank and irq (32 bits) into the hwirq */
+#define MAKE_HWIRQ(b, n)	((b << 5) | (n))
+#define HWIRQ_BANK(i)		(i >> 5)
+#define HWIRQ_BIT(i)		BIT(i & 0x1f)
+
+#define NR_IRQS_BANK0		8
+#define BANK0_HWIRQ_MASK	0xff
+/* Shortcuts can't be disabled so any unknown new ones need to be masked */
+#define SHORTCUT1_MASK		0x00007c00
+#define SHORTCUT2_MASK		0x001f8000
+#define SHORTCUT_SHIFT		10
+#define BANK1_HWIRQ		BIT(8)
+#define BANK2_HWIRQ		BIT(9)
+#define BANK0_VALID_MASK	(BANK0_HWIRQ_MASK | BANK1_HWIRQ | BANK2_HWIRQ \
+					| SHORTCUT1_MASK | SHORTCUT2_MASK)
+
+#define REG_FIQ_CONTROL		0x0c
+#define FIQ_CONTROL_ENABLE	BIT(7)
+
+#define NR_BANKS		3
+#define IRQS_PER_BANK		32
+
+static const int armctrl_reg_pending[] = { 0x04, 0x08, 0x00 };
+static const int armctrl_reg_enable[] = { 0x10, 0x14, 0x18 };
+static const int armctrl_reg_disable[] = { 0x1c, 0x20, 0x24 };
+static const int armctrl_bank_bits[] = { 32, 32, 8 };
+
+/* Copied from https://github.com/xinu-os/xinu/blob/master/system/platforms/arm-rpi/dispatch.c: */
+
+/* Number of IRQs shared between the GPU and ARM. These correspond to the IRQs
+ * that show up in the IRQ_pending_1 and IRQ_pending_2 registers.  */
+#define ARMCTRL_NUM_GPU_SHARED_IRQS     64
+
+/* Number of ARM-specific IRQs. These correspond to IRQs that show up in the
+ * first 8 bits of IRQ_basic_pending.  */
+#define ARMCTRL_NUM_ARM_SPECIFIC_IRQS   8
+
+#define ARMCTRL_NUM_IRQS (ARMCTRL_NUM_GPU_SHARED_IRQS + ARMCTRL_NUM_ARM_SPECIFIC_IRQS)
+#define L1_NUM_IRQS (32)
+#define NUM_IRQS (ARMCTRL_NUM_IRQS + L1_NUM_IRQS)
+
+static bool irq_enabled[NUM_IRQS];
+
+static void armctrl_irq_to_bank(unsigned int irq, int *bank, int *bank_bit) {
+	__ASSERT_NO_MSG(irq < ARMCTRL_NUM_IRQS);
+	*bank = 0;
+	*bank_bit = irq;
+	while (*bank_bit >= armctrl_bank_bits[*bank]) {
+		*bank_bit -= armctrl_bank_bits[*bank];
+		*bank += 1;
+
+		__ASSERT_NO_MSG(*bank <= 2);
+	}
+	__ASSERT_NO_MSG(0 <= *bank);
+	__ASSERT_NO_MSG(*bank <= 2);
+	__ASSERT_NO_MSG(0 <= *bank_bit);
+	__ASSERT_NO_MSG(*bank_bit < 32);
+}
+
+static void armctrl_irq_enable(unsigned int irq) {
+	int bank, bank_bit;
+	armctrl_irq_to_bank(irq, &bank, &bank_bit);
+	uintptr_t addr = BCM2836_ARMCTRL_BASE + armctrl_reg_enable[bank];
+
+	printk("armctrl_irq_enable irq=%d, bank=%d, bit=%d, addr=%p\n", irq, bank, bank_bit, (char *) addr);
+	sys_write32((1 << bank_bit), addr);
+}
+
+static void armctrl_irq_disable(unsigned int irq) {
+	int bank, bank_bit;
+	armctrl_irq_to_bank(irq, &bank, &bank_bit);
+	uintptr_t addr = BCM2836_ARMCTRL_BASE + armctrl_reg_disable[bank];
+
+	printk("armctrl_irq_enable irq=%d, bank=%d, bit=%d, addr=%p\n", irq, bank, bank_bit, (char *) addr);
+	sys_write32((1 << bank_bit), addr);
+}
+
+/* BCM2836 ARM-local peripherals manual, section 4.10 "Core interrupt sources" */
+/* QEMU Device Implementation: https://github.com/qemu/qemu/blob/918c81a53eb18ec4e9979876a39e86610cc565f4/hw/intc/bcm2836_control.c */
+
+static void l1_irq_enable(unsigned int l1_irq) {
+	__ASSERT_NO_MSG(l1_irq < L1_NUM_IRQS);
+
+	if (0 <= l1_irq && l1_irq <= 3) {
+		/* Core timer interrupts: CNT_PS_IRQ = 0, CNT_PNS_IRQ = 1, CNT_HP_IRQ = 2, CNT_V_IRQ = 3 */
+		int cpuid = arch_curr_cpu()->id;
+		intptr_t core_timer_interrupt_control_addr = 0x40000040 + cpuid * 4;
+		uint32_t val = sys_read32(core_timer_interrupt_control_addr);
+		val |= (1 << l1_irq);
+		sys_write32(val, core_timer_interrupt_control_addr);
+	} else {
+		printk("Warning: l1_irq_enable(%d) not implemented.\n", l1_irq);
+	}
+}
+
+static void l1_irq_disable(unsigned int l1_irq) {
+	__ASSERT_NO_MSG(l1_irq < L1_NUM_IRQS);
+	printk("Warning: l1_irq_disable(%d) not implemented.\n", l1_irq);
+}
+
+void z_soc_irq_init(void) {
+	/* Don't print anything here as C might not be initialized yet. */
+}
+
+int z_soc_irq_is_enabled(unsigned int irq) {
+	/* Manual does not explicitly state that reading from armctrl_reg_enable
+	 * indicates if an IRQ was enabled, also Xinu does not do it like
+	 * this. That's why we have irq_enabled. */
+	__ASSERT_NO_MSG(irq < ARMCTRL_NUM_IRQS);
+	return irq_enabled[irq];
+}
+
+void z_soc_irq_enable(unsigned int irq) {
+	if (irq < ARMCTRL_NUM_IRQS) {
+		armctrl_irq_enable(irq);
+		irq_enabled[irq] = true;
+	} else {
+		l1_irq_enable(irq - ARMCTRL_NUM_IRQS);
+	}
+}
+
+void z_soc_irq_disable(unsigned int irq) {
+	if (irq < ARMCTRL_NUM_IRQS) {
+		armctrl_irq_disable(irq);
+		irq_enabled[irq] = false;
+	} else {
+		l1_irq_disable(irq - ARMCTRL_NUM_IRQS);
+	}
+}
+
+void z_soc_irq_priority_set(unsigned int irq, unsigned int prio, unsigned int flags) {
+	/* Not supported. */
+
+	/* Peripheral Manual: There is no priority for any interrupt. If one
+	 * interrupt is much more important then all others it canbe routed to
+	 * the FIQ. */
+	return;
+}
+
+/* Called from HW IRQ context with interrupts disabled: Retrieve the currently
+ * active IRQ that should be handled.
+ *
+ * Resources:
+ * - https://embedded-xinu.readthedocs.io/en/latest/arm/rpi/BCM2835-Interrupt-Controller.html
+ */
+unsigned int z_soc_irq_get_active(void) {
+	int cpuid = arch_curr_cpu()->id;
+
+	/* printk("%s on cpu%d, stack at ~%p\n", __func__, cpuid, &cpuid); */
+
+	for (unsigned int irq = 0; irq < ARMCTRL_NUM_IRQS; irq++) {
+		int bank, bank_bit;
+		armctrl_irq_to_bank(irq, &bank, &bank_bit);
+
+		unsigned int bank_pending = sys_read32(BCM2836_ARMCTRL_BASE + armctrl_reg_pending[bank]);
+		bool is_pending = (bank_pending & (1 << bank_bit)) != 0;
+
+		if (is_pending) {
+			/* Clear pending to allow us to detect when this IRQ occurs again (nested irq). */
+			sys_write32(bank_pending & ~(1 << bank_bit), BCM2836_ARMCTRL_BASE + armctrl_reg_pending[bank]);
+			return irq;
+		}
+	}
+
+	intptr_t core_interrupt_sources_addr = 0x40000060 + cpuid * 4;
+	uint32_t pending = sys_read32(core_interrupt_sources_addr);
+	for (unsigned int l1_irq = 0; l1_irq < L1_NUM_IRQS; l1_irq++) {
+		unsigned int irq = ARMCTRL_NUM_IRQS + l1_irq;
+		if (pending & (1 << l1_irq)) {
+			/* https://developer.arm.com/architectures/learn-the-architecture/generic-timer/single-page */
+			if (l1_irq == 3) {
+				arm_arch_timer_irq_mask(true);
+			}
+			return irq;
+		}
+	}
+
+	__ASSERT_NO_MSG(false);
+	CODE_UNREACHABLE;
+}
+
+/* Mark irq as inactive (called in HW IRQ context after handler). */
+void z_soc_irq_eoi(unsigned int irq) {
+	if (irq < ARMCTRL_NUM_IRQS) {
+		printk("Warning: %s(%d)\n", __func__, irq);
+	} else {
+		unsigned int l1_irq = irq - ARMCTRL_NUM_IRQS;
+		if (l1_irq == 3) {
+			arm_arch_timer_irq_mask(false);
+		}
+	}
+}
diff --git a/soc/arm/bcm2837/linker.ld b/soc/arm/bcm2837/linker.ld
new file mode 100644
index 0000000000000000000000000000000000000000..fd1bad9e1d6d30ed1a4450dd67a4ce721c9ddd6a
--- /dev/null
+++ b/soc/arm/bcm2837/linker.ld
@@ -0,0 +1,8 @@
+/*
+ * Copyright (c) 2019 Carlo Caione <ccaione@baylibre.com>
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ */
+
+#include <arch/arm/aarch64/scripts/linker.ld>
diff --git a/soc/arm/bcm2837/mmu_regions.c b/soc/arm/bcm2837/mmu_regions.c
new file mode 100644
index 0000000000000000000000000000000000000000..24fe7566f44bd6cfa474b330aef2d3203f51f5e2
--- /dev/null
+++ b/soc/arm/bcm2837/mmu_regions.c
@@ -0,0 +1,54 @@
+/*
+ * Copyright 2019 Broadcom
+ * The term "Broadcom" refers to Broadcom Inc. and/or its subsidiaries.
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+#include <soc.h>
+#include <arch/arm/aarch64/arm_mmu.h>
+
+#define SZ_1K	1024
+
+static const struct arm_mmu_region mmu_regions[] = {
+#ifdef CONFIG_GIC_V3
+	MMU_REGION_FLAT_ENTRY("GIC",
+			      DT_REG_ADDR_BY_IDX(DT_INST(0, arm_gic), 0),
+			      DT_REG_SIZE_BY_IDX(DT_INST(0, arm_gic), 0),
+			      MT_DEVICE_nGnRnE | MT_RW | MT_SECURE),
+
+	MMU_REGION_FLAT_ENTRY("GIC",
+			      DT_REG_ADDR_BY_IDX(DT_INST(0, arm_gic), 1),
+			      DT_REG_SIZE_BY_IDX(DT_INST(0, arm_gic), 1),
+			      MT_DEVICE_nGnRnE | MT_RW | MT_SECURE),
+#else
+	MMU_REGION_FLAT_ENTRY("INTC_BCM2837_L1",
+			      0x40000000,
+			      0x1000,
+			      MT_DEVICE_nGnRnE | MT_RW | MT_SECURE),
+	MMU_REGION_FLAT_ENTRY("INTC_BCM2837_ARMCTRK",
+			      0x3f00b000,
+			      0x1000,
+			      MT_DEVICE_nGnRnE | MT_RW | MT_SECURE),
+#endif
+	MMU_REGION_FLAT_ENTRY("GP",
+			      0x3f200000,
+			      0x1000,
+			      MT_DEVICE_nGnRnE | MT_RW | MT_SECURE),
+#ifdef CONFIG_UART_PL011
+	MMU_REGION_FLAT_ENTRY("UART",
+			      DT_REG_ADDR(DT_INST(0, arm_pl011)),
+			      DT_REG_SIZE(DT_INST(0, arm_pl011)),
+			      MT_DEVICE_nGnRnE | MT_RW | MT_SECURE),
+#endif
+#if defined(CONFIG_SMP) || defined(CONFIG_ZTEST)
+	MMU_REGION_FLAT_ENTRY("SPINTABLE",
+			      0x00000000,
+			      0x1000,
+			      MT_DEVICE_nGnRnE | MT_RW | MT_SECURE),
+#endif
+};
+
+const struct arm_mmu_config mmu_config = {
+	.num_regions = ARRAY_SIZE(mmu_regions),
+	.mmu_regions = mmu_regions,
+};
diff --git a/soc/arm/bcm2837/plat_core.S b/soc/arm/bcm2837/plat_core.S
new file mode 100644
index 0000000000000000000000000000000000000000..c1ee72db6c1caf7c0ebaca6ef767916fc5dbac23
--- /dev/null
+++ b/soc/arm/bcm2837/plat_core.S
@@ -0,0 +1,32 @@
+/*
+ * Copyright 2020 Carlo Caione <ccaione@baylibre.com>
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+/**
+ *@file
+ *@brief plat/core specific init
+*/
+
+#include <toolchain.h>
+#include <linker/sections.h>
+#include <arch/cpu.h>
+
+_ASM_FILE_PROLOGUE
+
+GTEXT(z_arch_el3_plat_init)
+
+SECTION_FUNC(TEXT, z_arch_el3_plat_init)
+
+	mov	x20, x30
+
+#ifdef CONFIG_GIC_V3
+	/* Enable GIC v3 system interface */
+	mov_imm	x0, (ICC_SRE_ELx_DFB | ICC_SRE_ELx_DIB | \
+		     ICC_SRE_ELx_SRE | ICC_SRE_EL3_EN)
+	msr	ICC_SRE_EL3, x0
+#endif
+
+	mov	x30, x20
+	ret
diff --git a/soc/arm/bcm2837/soc.h b/soc/arm/bcm2837/soc.h
new file mode 100644
index 0000000000000000000000000000000000000000..889f634fe3e0997dc1e1afd4177eae669f915675
--- /dev/null
+++ b/soc/arm/bcm2837/soc.h
@@ -0,0 +1,19 @@
+/*
+ * Copyright (c) 2019 Carlo Caione <ccaione@baylibre.com>
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ */
+
+#ifndef _SOC_H_
+#define _SOC_H_
+
+#include <sys/util.h>
+
+#ifndef _ASMLANGUAGE
+
+#include <device.h>
+
+#endif /* !_ASMLANGUAGE */
+
+#endif /* _SOC_H_ */