summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAnson Huang <Anson.Huang@nxp.com>2017-03-14 05:59:28 +0800
committerAnson Huang <Anson.Huang@nxp.com>2017-07-12 23:17:24 +0800
commit96f0e1a3662f90526f47065f2687e9d66a3fa266 (patch)
tree085063af6f0077e93ade238acd0193fb1893b18b
parent39f3cc285c8f0a55f9d802433ea1274661a376a4 (diff)
Add i.MX8QXP support
Add i.MX8QXP platform support. Signed-off-by: Anson Huang <Anson.Huang@nxp.com> Signed-off-by: Bai Ping <ping.bai@nxp.com> Signed-off-by: Peng Fan <peng.fan@nxp.com>
-rw-r--r--plat/freescale/imx8qxp/imx8qxp_bl31_setup.c295
-rw-r--r--plat/freescale/imx8qxp/imx8qxp_psci.c217
-rw-r--r--plat/freescale/imx8qxp/include/platform_def.h80
-rw-r--r--plat/freescale/imx8qxp/platform.mk58
4 files changed, 650 insertions, 0 deletions
diff --git a/plat/freescale/imx8qxp/imx8qxp_bl31_setup.c b/plat/freescale/imx8qxp/imx8qxp_bl31_setup.c
new file mode 100644
index 00000000..d14d40aa
--- /dev/null
+++ b/plat/freescale/imx8qxp/imx8qxp_bl31_setup.c
@@ -0,0 +1,295 @@
+/*
+ * Copyright (c) 2015, ARM Limited and Contributors. All rights reserved.
+ * Copyright 2017 NXP
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * 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.
+ *
+ * Neither the name of ARM 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.
+ */
+
+#include <arch_helpers.h>
+#include <assert.h>
+#include <bl_common.h>
+#include <cci.h>
+#include <console.h>
+#include <context.h>
+#include <context_mgmt.h>
+#include <debug.h>
+#include <mmio.h>
+#include <platform.h>
+#include <platform_def.h>
+#include <plat_imx8.h>
+#include <sci/sci.h>
+#include <xlat_tables.h>
+#include <lpuart.h>
+
+/* linker defined symbols */
+extern unsigned long __RO_START__;
+extern unsigned long __RO_END__;
+extern unsigned long __BL31_END__;
+
+#if USE_COHERENT_MEM
+extern unsigned long __COHERENT_RAM_START__;
+extern unsigned long __COHERENT_RAM_END__;
+
+#define BL31_COHERENT_RAM_BASE (unsigned long)(&__COHERENT_RAM_START__)
+#define BL31_COHERENT_RAM_LIMIT (unsigned long)(&__COHERENT_RAM_END__)
+#endif
+
+sc_ipc_t ipc_handle;
+
+#define BL31_RO_BASE (unsigned long)(&__RO_START__)
+#define BL31_RO_LIMIT (unsigned long)(&__RO_END__)
+#define BL31_END (unsigned long)(&__BL31_END__)
+
+static entry_point_info_t bl32_image_ep_info;
+static entry_point_info_t bl33_image_ep_info;
+
+/* get SPSR for BL33 entry */
+static uint32_t get_spsr_for_bl33_entry(void)
+{
+ unsigned long el_status;
+ unsigned long mode;
+ uint32_t spsr;
+
+ /* figure out what mode we enter the non-secure world */
+ el_status = read_id_aa64pfr0_el1() >> ID_AA64PFR0_EL2_SHIFT;
+ el_status &= ID_AA64PFR0_ELX_MASK;
+
+ mode = (el_status) ? MODE_EL2 : MODE_EL1;
+
+ spsr = SPSR_64(mode, MODE_SP_ELX, DISABLE_ALL_EXCEPTIONS);
+ return spsr;
+}
+
+#if DEBUG_CONSOLE_A35
+/*
+ * Note:
+ * This piece code is from uboot, take care of license issue.
+ */
+static void lpuart32_serial_setbrg(unsigned int base, int baudrate)
+{
+ unsigned int sbr, osr, baud_diff, tmp_osr, tmp_sbr, tmp_diff, tmp;
+ unsigned int clk;
+ sc_pm_clock_rate_t rate;
+
+ sc_pm_get_clock_rate(ipc_handle, SC_R_UART_0, 2, &rate);
+
+ clk = (unsigned int)rate;
+
+ baud_diff = baudrate;
+ osr = 0;
+ sbr = 0;
+ for (tmp_osr = 4; tmp_osr <= 32; tmp_osr++)
+ {
+ tmp_sbr = (clk / (baudrate * tmp_osr));
+ if (tmp_sbr == 0)
+ tmp_sbr = 1;
+
+ /*calculate difference in actual buad w/ current values */
+ tmp_diff = ( clk / (tmp_osr * tmp_sbr));
+ tmp_diff = tmp_diff - baudrate;
+
+ /* select best values between sbr and sbr+1 */
+ if (tmp_diff > (baudrate - (clk / (tmp_osr * (tmp_sbr + 1))))) {
+ tmp_diff = baudrate - (clk / (tmp_osr * (tmp_sbr + 1)));
+ tmp_sbr++;
+ }
+
+ if (tmp_diff <= baud_diff) {
+ baud_diff = tmp_diff;
+ osr = tmp_osr;
+ sbr = tmp_sbr;
+ }
+ }
+
+ /*TODO handle buadrate outside acceptable rate
+ * if (baudDiff > ((config->baudRate_Bps / 100) * 3))
+ * {
+ * Unacceptable baud rate difference of more than 3%
+ * return kStatus_LPUART_BaudrateNotSupport;
+ * }
+ */
+ tmp = mmio_read_32(IMX_BOOT_UART_BASE + BAUD);
+
+ if ((osr >3) && (osr < 8))
+ tmp |= LPUART_BAUD_BOTHEDGE_MASK;
+
+ tmp &= ~LPUART_BAUD_OSR_MASK;
+ tmp |= LPUART_BAUD_OSR(osr-1);
+ tmp &= ~LPUART_BAUD_SBR_MASK;
+ tmp |= LPUART_BAUD_SBR(sbr);
+
+ /* explicitly disable 10 bit mode & set 1 stop bit */
+ tmp &= ~(LPUART_BAUD_M10_MASK | LPUART_BAUD_SBNS_MASK);
+
+ mmio_write_32(IMX_BOOT_UART_BASE + BAUD, tmp);
+}
+
+static int lpuart32_serial_init(unsigned int base)
+{
+ unsigned int tmp;
+
+ /*disable TX & RX before enabling clocks */
+ tmp = mmio_read_32(IMX_BOOT_UART_BASE + CTRL);
+ tmp &= ~(CTRL_TE | CTRL_RE);
+ mmio_write_32(IMX_BOOT_UART_BASE + CTRL, tmp);
+
+ mmio_write_32(IMX_BOOT_UART_BASE + MODIR, 0);
+ mmio_write_32(IMX_BOOT_UART_BASE + FIFO, ~(FIFO_TXFE | FIFO_RXFE));
+
+ mmio_write_32(IMX_BOOT_UART_BASE + MATCH, 0);
+
+ /*
+ * provide data bits, parity, stop bit, etc
+ */
+ lpuart32_serial_setbrg(base, IMX_BOOT_UART_BAUDRATE);
+
+ /* eight data bits no parity bit */
+ tmp = mmio_read_32(IMX_BOOT_UART_BASE + CTRL);
+ tmp &= ~(LPUART_CTRL_PE_MASK | LPUART_CTRL_PT_MASK | LPUART_CTRL_M_MASK);
+ mmio_write_32(IMX_BOOT_UART_BASE + CTRL, tmp);
+
+ mmio_write_32(IMX_BOOT_UART_BASE + CTRL , CTRL_RE | CTRL_TE);
+
+ mmio_write_32(IMX_BOOT_UART_BASE + DATA, 0x55);
+ mmio_write_32(IMX_BOOT_UART_BASE + DATA, 0x55);
+ mmio_write_32(IMX_BOOT_UART_BASE + DATA, 0x0A);
+
+ return 0;
+}
+#endif
+
+void bl31_early_platform_setup(bl31_params_t *from_bl2,
+ void *plat_params_from_bl2)
+{
+ /* open the IPC channel */
+ if (sc_ipc_open(&ipc_handle, SC_IPC_CH) != SC_ERR_NONE) {
+ /* No console available now */
+ while (1);
+ }
+#if DEBUG_CONSOLE_A35
+ /* This maybe updated, need to check SCFW */
+ #define SC_P_UART0_RX 30
+ #define SC_P_UART0_TX 31
+ #define SC_P_UART0_RTS_B 32
+ #define SC_P_UART0_CTS_B 33
+
+ /* Power up UART0 */
+ sc_pm_set_resource_power_mode(ipc_handle, SC_R_UART_0, SC_PM_PW_MODE_ON);
+
+ /* Set UART0 clock root to 80 MHz */
+ sc_pm_clock_rate_t rate = 80000000;
+ sc_pm_set_clock_rate(ipc_handle, SC_R_UART_0, 2, &rate);
+
+ /* Enable UART0 clock root */
+ sc_pm_clock_enable(ipc_handle, SC_R_UART_0, 2, true, false);
+
+ /* Configure UART pads */
+ sc_pad_set(ipc_handle, SC_P_UART0_RX, 0xc600004c);
+
+ sc_pad_set(ipc_handle, SC_P_UART0_TX, 0xc600004c);
+
+ sc_pad_set(ipc_handle, SC_P_UART0_RTS_B, 0xc600004c);
+
+ sc_pad_set(ipc_handle, SC_P_UART0_CTS_B, 0xc600004c);
+
+ lpuart32_serial_init(IMX_BOOT_UART_BASE);
+#endif
+
+#if DEBUG_CONSOLE
+ console_init(IMX_BOOT_UART_BASE, IMX_BOOT_UART_CLK_IN_HZ,
+ IMX_CONSOLE_BAUDRATE);
+#endif
+
+ /*
+ * tell BL3-1 where the non-secure software image is located
+ * and the entry state information.
+ */
+ bl33_image_ep_info.pc = PLAT_NS_IMAGE_OFFSET;
+ bl33_image_ep_info.spsr = get_spsr_for_bl33_entry();
+ SET_SECURITY_STATE(bl33_image_ep_info.h.attr, NON_SECURE);
+}
+
+void bl31_plat_arch_setup(void)
+{
+ /*
+ * add the mmap
+ * Change to 128KB?
+ * Fix Me
+ */
+ mmap_add_region(BL31_BASE, BL31_BASE, 0x10000,
+ MT_MEMORY | MT_RW);
+ mmap_add_region(BL31_BASE, BL31_BASE, BL31_RO_LIMIT - BL31_RO_BASE,
+ MT_MEMORY | MT_RO);
+ mmap_add_region(IMX_BOOT_UART_BASE, IMX_BOOT_UART_BASE,
+ 0x1000, MT_DEVICE | MT_RW);
+ mmap_add_region(0x5d1b0000, 0x5d1b0000, 0x10000,
+ MT_DEVICE | MT_RW);
+ mmap_add_region(PLAT_GICD_BASE, PLAT_GICD_BASE, 0x10000,
+ MT_DEVICE | MT_RW);
+ mmap_add_region(PLAT_GICR_BASE, PLAT_GICR_BASE, 0xc0000,
+ MT_DEVICE | MT_RW);
+// mmap_add_region(IMX_GPT0_BASE, IMX_GPT0_BASE, 0x10000,
+// MT_DEVICE | MT_RW);
+#if USE_COHERENT_MEM
+ mmap_add_region(BL31_COHERENT_RAM_BASE, BL31_COHERENT_RAM_BASE,
+ BL31_COHERENT_RAM_LIMIT - BL31_COHERENT_RAM_BASE,
+ MT_DEVICE | MT_RW);
+#endif
+
+ /* setup xlat table */
+ init_xlat_tables();
+
+ /* enable the MMU */
+ enable_mmu_el3(0);
+}
+
+void bl31_platform_setup(void)
+{
+ /* init the GICv3 cpu and distributor interface */
+ plat_gic_driver_init();
+ plat_gic_init();
+}
+
+entry_point_info_t *bl31_plat_get_next_image_ep_info(unsigned int type)
+{
+ if (type == NON_SECURE)
+ return &bl33_image_ep_info;
+ if (type == SECURE)
+ return &bl32_image_ep_info;
+
+ return NULL;
+}
+
+unsigned long long plat_get_syscnt_freq(void)
+{
+ return COUNTER_FREQUENCY;
+}
+
+unsigned int plat_get_syscnt_freq2(void)
+{
+ return COUNTER_FREQUENCY;
+}
diff --git a/plat/freescale/imx8qxp/imx8qxp_psci.c b/plat/freescale/imx8qxp/imx8qxp_psci.c
new file mode 100644
index 00000000..b2356ec0
--- /dev/null
+++ b/plat/freescale/imx8qxp/imx8qxp_psci.c
@@ -0,0 +1,217 @@
+/*
+ * Copyright (c) 2015, ARM Limited and Contributors. All rights reserved.
+ * Copyright 2017 NXP
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * 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.
+ *
+ * Neither the name of ARM 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.
+ */
+
+#include <arch.h>
+#include <arch_helpers.h>
+#include <debug.h>
+#include <plat_imx8.h>
+#include <psci.h>
+#include <sci/sci.h>
+
+extern sc_ipc_t ipc_handle;
+extern void mdelay(uint32_t msec);
+
+const unsigned char imx_power_domain_tree_desc[] =
+{
+ /* number of root nodes */
+ PWR_DOMAIN_AT_MAX_LVL,
+ /* number of child at the first node */
+ PLATFORM_CLUSTER_COUNT,
+ PLATFORM_CORE_COUNT,
+};
+
+const static int ap_core_index[PLATFORM_CORE_COUNT] = {
+ SC_R_A35_0, SC_R_A35_1, SC_R_A35_2, SC_R_A35_3
+};
+
+plat_local_state_t plat_get_target_pwr_state(unsigned int lvl,
+ const plat_local_state_t *target_state,
+ unsigned int ncpu)
+{
+ /* TODO */
+ return 0;
+}
+
+void imx8qxp_kill_cpu(unsigned int target_idx)
+{
+ tf_printf("kill cluster %d, cpu %d\n", target_idx / 4, target_idx % 4);
+
+ if (sc_pm_cpu_start(ipc_handle, ap_core_index[target_idx],
+ false, 0x80000000) != SC_ERR_NONE) {
+ ERROR("cluster %d core %d power down failed!\n",
+ target_idx / 4, target_idx % 4);
+ return;
+ }
+
+ if (sc_pm_set_resource_power_mode(ipc_handle, ap_core_index[target_idx],
+ SC_PM_PW_MODE_OFF) != SC_ERR_NONE) {
+ ERROR("cluster %d core %d power down failed!\n",
+ target_idx / 4, target_idx % 4);
+ return;
+ }
+}
+
+int imx_pwr_domain_on(u_register_t mpidr)
+{
+ int ret = PSCI_E_SUCCESS;
+ unsigned int cluster_id, cpu_id;
+
+ cluster_id = MPIDR_AFFLVL1_VAL(mpidr);
+ cpu_id = MPIDR_AFFLVL0_VAL(mpidr);
+
+ tf_printf("imx_pwr_domain_on cluster_id %d, cpu_id %d\n", cluster_id, cpu_id);
+
+ if (sc_pm_set_resource_power_mode(ipc_handle, ap_core_index[cpu_id],
+ SC_PM_PW_MODE_ON) != SC_ERR_NONE) {
+ ERROR("cluster0 core %d power on failed!\n", cpu_id);
+ ret = PSCI_E_INTERN_FAIL;
+ }
+
+ if (sc_pm_cpu_start(ipc_handle, ap_core_index[cpu_id],
+ true, 0x80000000) != SC_ERR_NONE) {
+ ERROR("boot cluster0 core %d failed!\n", cpu_id);
+ ret = PSCI_E_INTERN_FAIL;
+ }
+
+ return ret;
+}
+
+void imx_pwr_domain_on_finish(const psci_power_state_t *target_state)
+{
+ uint64_t mpidr = read_mpidr_el1();
+ unsigned int cluster_id = MPIDR_AFFLVL1_VAL(mpidr);
+ unsigned int cpu_id = MPIDR_AFFLVL0_VAL(mpidr);
+
+ /* program the GIC per cpu dist and rdist interface */
+ plat_gic_pcpu_init();
+
+ /* enable the GICv3 cpu interface */
+ plat_gic_cpuif_enable();
+
+ tf_printf("cluster:%d core:%d is on\n", cluster_id, cpu_id);
+}
+
+void imx_pwr_domain_off(const psci_power_state_t *target_state)
+{
+ u_register_t mpidr = read_mpidr_el1();
+ unsigned int cluster_id = MPIDR_AFFLVL1_VAL(mpidr);
+ unsigned int cpu_id = MPIDR_AFFLVL0_VAL(mpidr);
+
+ plat_gic_cpuif_disable();
+ tf_printf("turn off cluster:%d core:%d\n", cluster_id, cpu_id);
+}
+
+int imx_validate_ns_entrypoint(uintptr_t ns_entrypoint)
+{
+ /*
+ * U-Boot and ATFW are combined into one image, let ROM HAB
+ * validate the whole file.
+ */
+ return PSCI_E_SUCCESS;
+}
+
+int imx_validate_power_state(unsigned int power_state,
+ psci_power_state_t *req_state)
+{
+ int pwr_lvl = psci_get_pstate_pwrlvl(power_state);
+
+ if (pwr_lvl > PLAT_MAX_PWR_LVL)
+ return PSCI_E_INVALID_PARAMS;
+
+ /* Sanity check the requested afflvl */
+ if (psci_get_pstate_type(power_state) == PSTATE_TYPE_STANDBY) {
+ if (pwr_lvl != MPIDR_AFFLVL0)
+ return PSCI_E_INVALID_PARAMS;
+ /* power domain in standby state */
+ req_state->pwr_domain_state[pwr_lvl] = PLAT_MAX_RET_STATE;
+
+ return PSCI_E_SUCCESS;
+ }
+
+ return 0;
+}
+
+void imx_cpu_standby(plat_local_state_t cpu_state)
+{
+ dsb();
+
+ write_icc_igrpen1_el1(1);
+
+ write_scr_el3(read_scr_el3() | 0x4);
+ isb();
+
+ wfi();
+
+ write_icc_igrpen1_el1(0);
+ write_scr_el3(read_scr_el3() & (~0x4));
+ isb();
+}
+
+void imx_domain_suspend(const psci_power_state_t *target_state)
+{
+ //psci_power_down_wfi();
+}
+
+void imx_domain_suspend_finish(const psci_power_state_t *target_state)
+{
+ //psci_power_down_wfi();
+}
+
+void imx_get_sys_suspend_power_state(psci_power_state_t *req_state)
+{
+ unsigned int i;
+
+ for (i = IMX_PWR_LVL0; i <= PLAT_MAX_PWR_LVL; i++)
+ req_state->pwr_domain_state[i] = PLAT_MAX_RET_STATE;
+}
+
+static const plat_psci_ops_t imx_plat_psci_ops = {
+ .pwr_domain_on = imx_pwr_domain_on,
+ .pwr_domain_on_finish = imx_pwr_domain_on_finish,
+ .pwr_domain_off = imx_pwr_domain_off,
+ .validate_ns_entrypoint = imx_validate_ns_entrypoint,
+ .validate_power_state = imx_validate_power_state,
+ .cpu_standby = imx_cpu_standby,
+ .pwr_domain_suspend = imx_domain_suspend,
+ .pwr_domain_suspend_finish = imx_domain_suspend_finish,
+ .get_sys_suspend_power_state = imx_get_sys_suspend_power_state,
+};
+
+/* export the platform specific psci ops */
+int plat_setup_psci_ops(uintptr_t sec_entrypoint,
+ const plat_psci_ops_t **psci_ops)
+{
+ imx_mailbox_init(sec_entrypoint);
+ /* sec_entrypoint is used for warm reset */
+ *psci_ops = &imx_plat_psci_ops;
+
+ return 0;
+}
diff --git a/plat/freescale/imx8qxp/include/platform_def.h b/plat/freescale/imx8qxp/include/platform_def.h
new file mode 100644
index 00000000..d1de2aca
--- /dev/null
+++ b/plat/freescale/imx8qxp/include/platform_def.h
@@ -0,0 +1,80 @@
+/*
+ * Copyright (c) 2015, ARM Limited and Contributors. All rights reserved.
+ * Copyright 2017 NXP
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * 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.
+ *
+ * Neither the name of ARM 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.
+ */
+
+#define PLATFORM_LINKER_FORMAT "elf64-littleaarch64"
+#define PLATFORM_LINKER_ARCH aarch64
+
+#define PLATFORM_STACK_SIZE 0x400
+/* Fix Me! A35 */
+#define CACHE_WRITEBACK_GRANULE 64
+
+#define PLAT_PRIMARY_CPU 0x0
+#define PLATFORM_MAX_CPU_PER_CLUSTER 4
+#define PLATFORM_CLUSTER_COUNT 1
+#define PLATFORM_CORE_COUNT 4
+
+#define IMX_PWR_LVL0 MPIDR_AFFLVL0
+#define IMX_PWR_LVL1 MPIDR_AFFLVL1
+
+#define PWR_DOMAIN_AT_MAX_LVL 1
+#define PLAT_MAX_PWR_LVL 2
+#define PLAT_MAX_OFF_STATE 2
+#define PLAT_MAX_RET_STATE 1
+
+#define BL31_BASE 0x80000000
+#define BL31_LIMIT 0x80020000
+
+/* non-secure uboot base */
+#define PLAT_NS_IMAGE_OFFSET 0x80020000
+
+/* GICv3 base address */
+#define PLAT_GICD_BASE 0x51a00000
+#define PLAT_GICR_BASE 0x51b00000
+
+#define PLAT_FSL_ADDR_SPACE_SIZE (1ull << 32)
+#define PLAT_VIRT_ADDR_SPACE_SIZE (1ull << 32)
+#define PLAT_PHY_ADDR_SPACE_SIZE (1ull << 32)
+
+#define MAX_XLAT_TABLES 4
+#define MAX_MMAP_REGIONS 8
+
+#define IMX_BOOT_UART_BASE 0x5a060000
+#define IMX_BOOT_UART_BAUDRATE 4000000
+#define IMX_BOOT_UART_CLK_IN_HZ 24000000
+#define PLAT_CRASH_UART_BASE IMX_BOOT_UART_BASE
+#define PLAT__CRASH_UART_CLK_IN_HZ 24000000
+#define IMX_CONSOLE_BAUDRATE 4000000
+
+#define COUNTER_FREQUENCY 8000000 /* 8MHz */
+
+#define DEBUG_CONSOLE 1
+#define DEBUG_CONSOLE_A35 1
+#define PLAT_IMX8QXP 1
diff --git a/plat/freescale/imx8qxp/platform.mk b/plat/freescale/imx8qxp/platform.mk
new file mode 100644
index 00000000..efcd5216
--- /dev/null
+++ b/plat/freescale/imx8qxp/platform.mk
@@ -0,0 +1,58 @@
+#
+# Copyright (c) 2015, ARM Limited and Contributors. All rights reserved.
+# Copyright 2017 NXP
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions are met:
+#
+# Redistributions of source code must retain the above copyright notice, this
+# list of conditions and the following disclaimer.
+#
+# 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.
+#
+# Neither the name of ARM 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.
+#
+
+PLAT_INCLUDES := -Iplat/freescale/imx8qxp/include \
+ -Iplat/freescale/common/include \
+
+PLAT_GIC_SOURCES := drivers/arm/gic/v3/gicv3_helpers.c \
+ drivers/arm/gic/v3/gicv3_main.c \
+ drivers/arm/gic/common/gic_common.c \
+ plat/common/plat_gicv3.c \
+ plat/freescale/common/plat_imx8_gic.c
+
+BL31_SOURCES += plat/freescale/common/lpuart_console.S \
+ plat/freescale/common/imx8_helpers.S \
+ plat/freescale/imx8qxp/imx8qxp_bl31_setup.c \
+ plat/freescale/imx8qxp/imx8qxp_psci.c \
+ plat/freescale/common/imx8_topology.c \
+ lib/xlat_tables/xlat_tables_common.c \
+ lib/xlat_tables/aarch64/xlat_tables.c \
+ lib/cpus/aarch64/cortex_a35.S \
+ drivers/console/aarch64/console.S \
+ ${PLAT_GIC_SOURCES} \
+
+include plat/freescale/common/sci/sci_api.mk
+
+ENABLE_PLAT_COMPAT := 0
+USE_COHERENT_MEM := 0
+RESET_TO_BL31 := 1
+ERROR_DEPRECATED := 1
+ARM_GIC_ARCH := 3