summaryrefslogtreecommitdiff
path: root/drivers
diff options
context:
space:
mode:
authorAnson Huang <Anson.Huang@nxp.com>2017-01-19 03:59:00 +0800
committerJason Liu <jason.hui.liu@nxp.com>2019-02-12 10:25:35 +0800
commit7e9ab097fb6f098b03246fa3ac4ef2330a66ba07 (patch)
tree79e25264b7890721ca8dfa3521bc9cbf452745ac /drivers
parentca5639ee39f696090aaf5e236358abd6f09770eb (diff)
MLK-13911-5 soc: scfw: imx8: add SCFW
Add i.MX8 SCFW API support. Based on below commit: (fcd0efb5f2550712bd7d27f1279e51f7f687f71d) Fix MX8 MU driver to follow Linux coding conventions. Remove unused functions. Signed-off-by: Anson Huang <Anson.Huang@nxp.com> Signed-off-by: Ranjani Vaidyanathan <Ranjani.Vaidyanathan@nxp.com> Added to drivers/soc/imx instead of drivers/soc/imx8 Skipped imx8 imx_rpmsg code Signed-off-by: Leonard Crestez <leonard.crestez@nxp.com>
Diffstat (limited to 'drivers')
-rw-r--r--drivers/soc/Makefile2
-rw-r--r--drivers/soc/imx/Makefile2
-rw-r--r--drivers/soc/imx/mu/Makefile1
-rw-r--r--drivers/soc/imx/mu/mx8_mu.c78
-rw-r--r--drivers/soc/imx/mu/mx8_mu.h36
-rw-r--r--drivers/soc/imx/sc/Makefile8
-rw-r--r--drivers/soc/imx/sc/main/ipc.c366
-rw-r--r--drivers/soc/imx/sc/main/rpc.h124
-rw-r--r--drivers/soc/imx/sc/svc/irq/rpc.h53
-rw-r--r--drivers/soc/imx/sc/svc/irq/rpc_clnt.c74
-rw-r--r--drivers/soc/imx/sc/svc/misc/rpc.h70
-rw-r--r--drivers/soc/imx/sc/svc/misc/rpc_clnt.c405
-rw-r--r--drivers/soc/imx/sc/svc/pad/rpc.h67
-rw-r--r--drivers/soc/imx/sc/svc/pad/rpc_clnt.c453
-rw-r--r--drivers/soc/imx/sc/svc/pm/rpc.h70
-rw-r--r--drivers/soc/imx/sc/svc/pm/rpc_clnt.c415
-rw-r--r--drivers/soc/imx/sc/svc/rm/rpc.h82
-rw-r--r--drivers/soc/imx/sc/svc/rm/rpc_clnt.c637
-rw-r--r--drivers/soc/imx/sc/svc/timer/rpc.h64
-rw-r--r--drivers/soc/imx/sc/svc/timer/rpc_clnt.c322
20 files changed, 3328 insertions, 1 deletions
diff --git a/drivers/soc/Makefile b/drivers/soc/Makefile
index 36dec140ea0d..e60a4a710c39 100644
--- a/drivers/soc/Makefile
+++ b/drivers/soc/Makefile
@@ -9,7 +9,7 @@ obj-y += bcm/
obj-$(CONFIG_ARCH_DOVE) += dove/
obj-$(CONFIG_MACH_DOVE) += dove/
obj-y += fsl/
-obj-$(CONFIG_ARCH_MXC) += imx/
+obj-y += imx/
obj-$(CONFIG_SOC_XWAY) += lantiq/
obj-$(CONFIG_ARCH_MEDIATEK) += mediatek/
obj-$(CONFIG_ARCH_MESON) += amlogic/
diff --git a/drivers/soc/imx/Makefile b/drivers/soc/imx/Makefile
index aab41a5cc317..49fdc3dc8ea2 100644
--- a/drivers/soc/imx/Makefile
+++ b/drivers/soc/imx/Makefile
@@ -1,2 +1,4 @@
obj-$(CONFIG_HAVE_IMX_GPC) += gpc.o
obj-$(CONFIG_IMX7_PM_DOMAINS) += gpcv2.o
+obj-$(CONFIG_ARCH_FSL_IMX8QM) += mu/
+obj-$(CONFIG_ARCH_FSL_IMX8QM) += sc/
diff --git a/drivers/soc/imx/mu/Makefile b/drivers/soc/imx/mu/Makefile
new file mode 100644
index 000000000000..922308c3f90f
--- /dev/null
+++ b/drivers/soc/imx/mu/Makefile
@@ -0,0 +1 @@
+obj-y += mx8_mu.o
diff --git a/drivers/soc/imx/mu/mx8_mu.c b/drivers/soc/imx/mu/mx8_mu.c
new file mode 100644
index 000000000000..ed341d695af4
--- /dev/null
+++ b/drivers/soc/imx/mu/mx8_mu.c
@@ -0,0 +1,78 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+#include <linux/err.h>
+#include <linux/io.h>
+#include "mx8_mu.h"
+
+
+/*!
+ * This function enables specific RX full interrupt.
+ */
+void MU_EnableRxFullInt(void __iomem *base, uint32_t index)
+{
+ uint32_t reg = readl_relaxed(base + MU_ACR_OFFSET1);
+
+ reg &= ~(MU_CR_GIRn_MASK1 | MU_CR_NMI_MASK1);
+ reg |= ~MU_CR_RIE0_MASK1 >> index;
+ writel_relaxed(reg, base + MU_ACR_OFFSET1);
+}
+
+/*!
+ * This function enables specific general purpose interrupt.
+ */
+void MU_EnableGeneralInt(void __iomem *base, uint32_t index)
+{
+ uint32_t reg = readl_relaxed(base + MU_ACR_OFFSET1);
+
+ reg &= ~(MU_CR_GIRn_MASK1 | MU_CR_NMI_MASK1);
+ reg |= MU_CR_GIE0_MASK1 >> index;
+ writel_relaxed(reg, base + MU_ACR_OFFSET1);
+}
+
+/*
+ * Wait and send message to the other core.
+ */
+void MU_SendMessage(void __iomem *base, uint32_t regIndex, uint32_t msg)
+{
+ uint32_t mask = MU_SR_TE0_MASK1 >> regIndex;
+
+ /* Wait TX register to be empty. */
+ while (!(readl_relaxed(base + MU_ASR_OFFSET1) & mask))
+ ;
+ writel_relaxed(msg, base + MU_ATR0_OFFSET1 + (regIndex * 4));
+}
+
+
+/*
+ * Wait to receive message from the other core.
+ */
+void MU_ReceiveMsg(void __iomem *base, uint32_t regIndex, uint32_t *msg)
+{
+ uint32_t mask = MU_SR_RF0_MASK1 >> regIndex;
+
+ /* Wait RX register to be full. */
+ while (!(readl_relaxed(base + MU_ASR_OFFSET1) & mask))
+ ;
+ *msg = readl_relaxed(base + MU_ARR0_OFFSET1 + (regIndex * 4));
+}
+
+
+
+void MU_Init(void __iomem *base)
+{
+ uint32_t reg;
+
+ reg = readl_relaxed(base + MU_ACR_OFFSET1);
+ /* Clear GIEn, RIEn, TIEn, GIRn and ABFn. */
+ reg &= ~(MU_CR_GIEn_MASK1 | MU_CR_RIEn_MASK1 | MU_CR_TIEn_MASK1
+ | MU_CR_GIRn_MASK1 | MU_CR_NMI_MASK1 | MU_CR_Fn_MASK1);
+ writel_relaxed(reg, base + MU_ACR_OFFSET1);
+}
+
+/**@}*/
+
diff --git a/drivers/soc/imx/mu/mx8_mu.h b/drivers/soc/imx/mu/mx8_mu.h
new file mode 100644
index 000000000000..7d428acf229e
--- /dev/null
+++ b/drivers/soc/imx/mu/mx8_mu.h
@@ -0,0 +1,36 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+#define MU_ATR0_OFFSET1 0x0
+#define MU_ARR0_OFFSET1 0x10
+#define MU_ASR_OFFSET1 0x20
+#define MU_ACR_OFFSET1 0x24
+#define MU_TR_COUNT1 4
+#define MU_RR_COUNT1 4
+
+#define MU_CR_GIEn_MASK1 (0xF << 28)
+#define MU_CR_RIEn_MASK1 (0xF << 24)
+#define MU_CR_TIEn_MASK1 (0xF << 20)
+#define MU_CR_GIRn_MASK1 (0xF << 16)
+#define MU_CR_NMI_MASK1 (1 << 3)
+#define MU_CR_Fn_MASK1 0x7
+
+#define MU_SR_TE0_MASK1 (1 << 23)
+#define MU_SR_RF0_MASK1 (1 << 27)
+#define MU_CR_RIE0_MASK1 (1 << 27)
+#define MU_CR_GIE0_MASK1 (1 << 31)
+
+#define MU_TR_COUNT 4
+#define MU_RR_COUNT 4
+
+
+void MU_Init(void __iomem *base);
+void MU_SendMessage(void __iomem *base, uint32_t regIndex, uint32_t msg);
+void MU_ReceiveMsg(void __iomem *base, uint32_t regIndex, uint32_t *msg);
+void MU_EnableGeneralInt(void __iomem *base, uint32_t index);
+void MU_EnableRxFullInt(void __iomem *base, uint32_t index);
+
diff --git a/drivers/soc/imx/sc/Makefile b/drivers/soc/imx/sc/Makefile
new file mode 100644
index 000000000000..851c687ce7b3
--- /dev/null
+++ b/drivers/soc/imx/sc/Makefile
@@ -0,0 +1,8 @@
+obj-y += main/ipc.o
+obj-y += svc/misc/rpc_clnt.o
+obj-y += svc/pad/rpc_clnt.o
+obj-y += svc/pm/rpc_clnt.o
+obj-y += svc/rm/rpc_clnt.o
+obj-y += svc/timer/rpc_clnt.o
+obj-y += svc/irq/rpc_clnt.o
+
diff --git a/drivers/soc/imx/sc/main/ipc.c b/drivers/soc/imx/sc/main/ipc.c
new file mode 100644
index 000000000000..0be06479bb03
--- /dev/null
+++ b/drivers/soc/imx/sc/main/ipc.c
@@ -0,0 +1,366 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/* Includes */
+#include <linux/err.h>
+#include <linux/kernel.h>
+#include <linux/of.h>
+#include <linux/of_irq.h>
+#include <linux/of_address.h>
+#include <linux/of_device.h>
+#include <linux/of_fdt.h>
+#include <linux/interrupt.h>
+#include <linux/irq.h>
+
+#include <soc/imx8/sc/svc/irq/api.h>
+#include <soc/imx8/sc/ipc.h>
+#include <soc/imx8/sc/sci.h>
+
+#include "../../mu/mx8_mu.h"
+#include "rpc.h"
+
+/* Local Defines */
+#define MU_SIZE 0x10000
+
+/* Local Types */
+unsigned int scu_mu_id;
+static void __iomem *mu_base_virtaddr;
+static struct delayed_work scu_mu_work;
+static sc_ipc_t mu_ipcHandle;
+
+/* Local functions */
+
+/* Local variables */
+static uint32_t gIPCport;
+static bool scu_mu_init;
+
+DEFINE_MUTEX(scu_mu_mutex);
+
+static BLOCKING_NOTIFIER_HEAD(SCU_notifier_chain);
+
+EXPORT_SYMBOL(sc_pm_set_resource_power_mode);
+EXPORT_SYMBOL(sc_pm_get_resource_power_mode);
+EXPORT_SYMBOL(sc_pm_cpu_start);
+EXPORT_SYMBOL(sc_misc_set_control);
+EXPORT_SYMBOL(sc_pm_clock_enable);
+EXPORT_SYMBOL(sc_pm_set_clock_rate);
+/*--------------------------------------------------------------------------*/
+/* RPC command/response */
+/*--------------------------------------------------------------------------*/
+void sc_call_rpc(sc_ipc_t handle, sc_rpc_msg_t *msg, bool no_resp)
+{
+ if (in_interrupt()) {
+ pr_warn("Cannot make SC IPC calls from an interrupt context\n");
+ dump_stack();
+ return;
+ }
+ mutex_lock(&scu_mu_mutex);
+
+ sc_ipc_write(handle, msg);
+ if (!no_resp)
+ sc_ipc_read(handle, msg);
+
+ mutex_unlock(&scu_mu_mutex);
+}
+EXPORT_SYMBOL(sc_call_rpc);
+
+/*--------------------------------------------------------------------------*/
+/* Get MU base address for specified IPC channel */
+/*--------------------------------------------------------------------------*/
+static uint32_t *sc_ipc_get_mu_base(uint32_t id)
+{
+ uint32_t *base;
+
+ /* Check parameters */
+ if (id >= SC_NUM_IPC)
+ base = NULL;
+ else
+ base = (uint32_t *) (mu_base_virtaddr + (id * MU_SIZE));
+
+ return base;
+}
+
+/*--------------------------------------------------------------------------*/
+/* Get the MU ID used by Linux */
+/*--------------------------------------------------------------------------*/
+int sc_ipc_getMuID(uint32_t *mu_id)
+{
+ if (scu_mu_init) {
+ *mu_id = scu_mu_id;
+ return SC_ERR_NONE;
+ }
+ return SC_ERR_UNAVAILABLE;
+}
+
+EXPORT_SYMBOL(sc_ipc_getMuID);
+
+/*--------------------------------------------------------------------------*/
+/* Open an IPC channel */
+/*--------------------------------------------------------------------------*/
+sc_err_t sc_ipc_requestInt(sc_ipc_t *handle, uint32_t id)
+{
+ return SC_ERR_NONE;
+}
+
+/*--------------------------------------------------------------------------*/
+/* Open an IPC channel */
+/*--------------------------------------------------------------------------*/
+sc_err_t sc_ipc_open(sc_ipc_t *handle, uint32_t id)
+{
+ uint32_t *base;
+
+ mutex_lock(&scu_mu_mutex);
+
+ if (!scu_mu_init) {
+ mutex_unlock(&scu_mu_mutex);
+ return SC_ERR_UNAVAILABLE;
+ }
+ /* Get MU base associated with IPC channel */
+ base = sc_ipc_get_mu_base(id);
+
+ if (base == NULL) {
+ mutex_unlock(&scu_mu_mutex);
+ return SC_ERR_IPC;
+ }
+
+ *handle = (sc_ipc_t) task_pid_vnr(current);
+
+ mutex_unlock(&scu_mu_mutex);
+
+ return SC_ERR_NONE;
+}
+EXPORT_SYMBOL(sc_ipc_open);
+/*--------------------------------------------------------------------------*/
+/* Close an IPC channel */
+/*--------------------------------------------------------------------------*/
+void sc_ipc_close(sc_ipc_t handle)
+{
+ uint32_t *base;
+
+ mutex_lock(&scu_mu_mutex);
+
+ if (!scu_mu_init) {
+ mutex_unlock(&scu_mu_mutex);
+ return;
+ }
+
+ /* Get MU base associated with IPC channel */
+ base = sc_ipc_get_mu_base(gIPCport);
+
+ /* TBD ***** What needs to be done here? */
+ mutex_unlock(&scu_mu_mutex);
+}
+EXPORT_SYMBOL(sc_ipc_close);
+
+/*!
+ * This function reads a message from an IPC channel.
+ *
+ * @param[in] ipc id of channel read from
+ * @param[out] data pointer to message buffer to read
+ *
+ * This function will block if no message is available to be read.
+ */
+void sc_ipc_read(sc_ipc_t handle, void *data)
+{
+ uint32_t *base;
+ uint8_t count = 0;
+ sc_rpc_msg_t *msg = (sc_rpc_msg_t *) data;
+
+ /* Get MU base associated with IPC channel */
+ base = sc_ipc_get_mu_base(gIPCport);
+
+ if ((base == NULL) || (msg == NULL))
+ return;
+
+ /* Read first word */
+ MU_ReceiveMsg(base, 0, (uint32_t *) msg);
+ count++;
+
+ /* Check size */
+ if (msg->size > SC_RPC_MAX_MSG) {
+ *((uint32_t *) msg) = 0;
+ return;
+ }
+
+ /* Read remaining words */
+ while (count < msg->size) {
+ MU_ReceiveMsg(base, count % MU_RR_COUNT,
+ &(msg->DATA.u32[count - 1]));
+ count++;
+ }
+}
+
+/*!
+ * This function writes a message to an IPC channel.
+ *
+ * @param[in] ipc id of channel to write to
+ * @param[in] data pointer to message buffer to write
+ *
+ * This function will block if the outgoing buffer is full.
+ */
+void sc_ipc_write(sc_ipc_t handle, void *data)
+{
+ uint32_t *base;
+ uint8_t count = 0;
+ sc_rpc_msg_t *msg = (sc_rpc_msg_t *) data;
+
+ /* Get MU base associated with IPC channel */
+ base = sc_ipc_get_mu_base(gIPCport);
+
+ if ((base == NULL) || (msg == NULL))
+ return;
+
+ /* Check size */
+ if (msg->size > SC_RPC_MAX_MSG)
+ return;
+
+ /* Write first word */
+ MU_SendMessage(base, 0, *((uint32_t *) msg));
+ count++;
+
+ /* Write remaining words */
+ while (count < msg->size) {
+ MU_SendMessage(base, count % MU_TR_COUNT, msg->DATA.u32[count - 1]);
+ count++;
+ }
+}
+
+int register_scu_notifier(struct notifier_block *nb)
+{
+ return blocking_notifier_chain_register(&SCU_notifier_chain, nb);
+}
+
+EXPORT_SYMBOL(register_scu_notifier);
+
+int unregister_scu_notifier(struct notifier_block *nb)
+{
+ return blocking_notifier_chain_unregister(&SCU_notifier_chain, nb);
+}
+
+EXPORT_SYMBOL(unregister_scu_notifier);
+
+static int SCU_notifier_call_chain(unsigned long val)
+{
+ return (blocking_notifier_call_chain(&SCU_notifier_chain, val, NULL) ==
+ NOTIFY_BAD) ? -EINVAL : 0;
+}
+
+static void scu_mu_work_handler(struct work_struct *work)
+{
+ uint32_t irq_status;
+ sc_err_t sciErr;
+
+ /* Figure out what caused the interrupt. */
+ sciErr = sc_irq_status(mu_ipcHandle, SC_R_MU_0A, SC_IRQ_GROUP_TEMP,
+ &irq_status);
+
+ if (irq_status & (SC_IRQ_TEMP_PMIC0_HIGH | SC_IRQ_TEMP_PMIC1_HIGH))
+ SCU_notifier_call_chain(irq_status);
+
+ sciErr = sc_irq_status(mu_ipcHandle, SC_R_MU_0A, SC_IRQ_GROUP_RTC,
+ &irq_status);
+
+ if (irq_status & SC_IRQ_RTC)
+ SCU_notifier_call_chain(irq_status);
+}
+
+static irqreturn_t imx8_scu_mu_isr(int irq, void *param)
+{
+ u32 irqs;
+
+ irqs = (readl_relaxed(mu_base_virtaddr + 0x20) & (0xf << 28));
+ if (irqs) {
+ /* Clear the General Interrupt */
+ writel_relaxed(irqs, mu_base_virtaddr + 0x20);
+ /* Setup a bottom-half to handle the irq work. */
+ schedule_delayed_work(&scu_mu_work, 0);
+ }
+ return IRQ_HANDLED;
+}
+
+/*Initialization of the MU code. */
+int __init imx8_mu_init(void)
+{
+ struct device_node *np;
+ u32 irq;
+ int err;
+ sc_err_t sciErr;
+
+ /*
+ * Get the address of MU to be used for communication with the SCU
+ */
+ np = of_find_compatible_node(NULL, NULL, "fsl,imx8-mu");
+ if (!np) {
+ pr_info("Cannot find MU entry in device tree\n");
+ return 0;
+ }
+ mu_base_virtaddr = of_iomap(np, 0);
+ WARN_ON(!mu_base_virtaddr);
+
+ err = of_property_read_u32_index(np, "fsl,scu_ap_mu_id", 0, &scu_mu_id);
+ if (err)
+ pr_info("imx8_mu_init: Cannot get mu_id err = %d\n", err);
+
+ irq = of_irq_get(np, 0);
+
+ err = request_irq(irq, imx8_scu_mu_isr,
+ IRQF_EARLY_RESUME, "imx8_mu_isr", NULL);
+
+ if (err) {
+ pr_info("imx8_mu_init :request_irq failed %d, err = %d\n", irq,
+ err);
+ }
+
+ if (!scu_mu_init) {
+ uint32_t i;
+
+ INIT_DELAYED_WORK(&scu_mu_work, scu_mu_work_handler);
+
+ /* Init MU */
+ MU_Init(mu_base_virtaddr);
+
+#if 1
+ /* Enable all RX interrupts */
+ for (i = 0; i < MU_RR_COUNT; i++)
+ MU_EnableGeneralInt(mu_base_virtaddr, i);
+#endif
+ gIPCport = scu_mu_id;
+ scu_mu_init = true;
+ }
+
+ sciErr = sc_ipc_open(&mu_ipcHandle, scu_mu_id);
+ if (sciErr != SC_ERR_NONE) {
+ pr_info("Cannot open MU channel to SCU\n");
+ return sciErr;
+ };
+
+ /* Request for the high temp interrupt. */
+ sciErr = sc_irq_enable(mu_ipcHandle, SC_R_MU_0A, SC_IRQ_GROUP_TEMP,
+ SC_IRQ_TEMP_PMIC0_HIGH, true);
+
+ if (sciErr)
+ pr_info("Cannot request PMIC0_TEMP interrupt\n");
+
+ /* Request for the high temp interrupt. */
+ sciErr = sc_irq_enable(mu_ipcHandle, SC_R_MU_0A, SC_IRQ_GROUP_TEMP,
+ SC_IRQ_TEMP_PMIC1_HIGH, true);
+
+ if (sciErr)
+ pr_info("Cannot request PMIC1_TEMP interrupt\n");
+
+ /* Request for the rtc alarm interrupt. */
+ sciErr = sc_irq_enable(mu_ipcHandle, SC_R_MU_0A, SC_IRQ_GROUP_RTC,
+ SC_IRQ_RTC, true);
+
+ if (sciErr)
+ pr_info("Cannot request ALARM_RTC interrupt\n");
+
+ pr_info("*****Initialized MU\n");
+ return scu_mu_id;
+}
+
+early_initcall(imx8_mu_init);
diff --git a/drivers/soc/imx/sc/main/rpc.h b/drivers/soc/imx/sc/main/rpc.h
new file mode 100644
index 000000000000..85cff2315f65
--- /dev/null
+++ b/drivers/soc/imx/sc/main/rpc.h
@@ -0,0 +1,124 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * Header file for the RPC implementation.
+ */
+
+#ifndef _SC_RPC_H
+#define _SC_RPC_H
+
+/* Includes */
+
+#include <soc/imx8/sc/types.h>
+#include <soc/imx8/sc/ipc.h>
+
+/* Defines */
+
+#define SC_RPC_VERSION 1
+
+#define SC_RPC_MAX_MSG 8
+
+#define RPC_VER(MSG) ((MSG)->version)
+#define RPC_SIZE(MSG) ((MSG)->size)
+#define RPC_SVC(MSG) ((MSG)->svc)
+#define RPC_FUNC(MSG) ((MSG)->func)
+#define RPC_R8(MSG) ((MSG)->func)
+#define RPC_I32(MSG, IDX) ((MSG)->DATA.i32[(IDX) / 4])
+#define RPC_I16(MSG, IDX) ((MSG)->DATA.i16[(IDX) / 2])
+#define RPC_I8(MSG, IDX) ((MSG)->DATA.i8[(IDX)])
+#define RPC_U32(MSG, IDX) ((MSG)->DATA.u32[(IDX) / 4])
+#define RPC_U16(MSG, IDX) ((MSG)->DATA.u16[(IDX) / 2])
+#define RPC_U8(MSG, IDX) ((MSG)->DATA.u8[(IDX)])
+
+/* Types */
+
+typedef enum sc_rpc_svc_e {
+ SC_RPC_SVC_UNKNOWN = 0,
+ SC_RPC_SVC_RETURN = 1,
+ SC_RPC_SVC_PM = 2,
+ SC_RPC_SVC_RM = 3,
+ SC_RPC_SVC_TIMER = 5,
+ SC_RPC_SVC_PAD = 6,
+ SC_RPC_SVC_MISC = 7,
+ SC_RPC_SVC_IRQ = 8,
+ SC_RPC_SVC_ABORT = 9
+} sc_rpc_svc_t;
+
+typedef struct sc_rpc_msg_s {
+ uint8_t version;
+ uint8_t size;
+ uint8_t svc;
+ uint8_t func;
+ union {
+ int32_t i32[(SC_RPC_MAX_MSG - 1)];
+ int16_t i16[(SC_RPC_MAX_MSG - 1) * 2];
+ int8_t i8[(SC_RPC_MAX_MSG - 1) * 4];
+ uint32_t u32[(SC_RPC_MAX_MSG - 1)];
+ uint16_t u16[(SC_RPC_MAX_MSG - 1) * 2];
+ uint8_t u8[(SC_RPC_MAX_MSG - 1) * 4];
+ } DATA;
+} sc_rpc_msg_t;
+
+typedef enum sc_rpc_async_state_e {
+ SC_RPC_ASYNC_STATE_RD_START = 0,
+ SC_RPC_ASYNC_STATE_RD_ACTIVE = 1,
+ SC_RPC_ASYNC_STATE_RD_DONE = 2,
+ SC_RPC_ASYNC_STATE_WR_START = 3,
+ SC_RPC_ASYNC_STATE_WR_ACTIVE = 4,
+ SC_RPC_ASYNC_STATE_WR_DONE = 5,
+} sc_rpc_async_state_t;
+
+typedef struct sc_rpc_async_msg_s {
+ sc_rpc_async_state_t state;
+ uint8_t wordIdx;
+ sc_rpc_msg_t msg;
+ uint32_t timeStamp;
+} sc_rpc_async_msg_t;
+
+/* Functions */
+
+/*!
+ * This is an internal function to send an RPC message over an IPC
+ * channel. It is called by client-side SCFW API function shims.
+ *
+ * @param[in] ipc IPC handle
+ * @param[in,out] msg handle to a message
+ * @param[in] no_resp response flag
+ *
+ * If \a no_resp is false then this function waits for a response
+ * and returns the result in \a msg.
+ */
+void sc_call_rpc(sc_ipc_t ipc, sc_rpc_msg_t *msg, bool no_resp);
+
+/*!
+ * This is an internal function to dispath an RPC call that has
+ * arrived via IPC over an MU. It is called by server-side SCFW.
+ *
+ * @param[in] mu MU message arrived on
+ * @param[in,out] msg handle to a message
+ *
+ * The function result is returned in \a msg.
+ */
+void sc_rpc_dispatch(sc_rsrc_t mu, sc_rpc_msg_t *msg);
+
+/*!
+ * This function translates an RPC message and forwards on to the
+ * normal RPC API. It is used only by hypervisors.
+ *
+ * @param[in] ipc IPC handle
+ * @param[in,out] msg handle to a message
+ *
+ * This function decodes a message, calls macros to translate the
+ * resources, pads, addresses, partitions, memory regions, etc. and
+ * then forwards on to the hypervisors SCFW API.Return results are
+ * translated back abd placed back into the message to be returned
+ * to the original API.
+ */
+void sc_rpc_xlate(sc_ipc_t ipc, sc_rpc_msg_t *msg);
+
+#endif /* _SC_RPC_H */
diff --git a/drivers/soc/imx/sc/svc/irq/rpc.h b/drivers/soc/imx/sc/svc/irq/rpc.h
new file mode 100644
index 000000000000..93ce7c3b87a3
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/irq/rpc.h
@@ -0,0 +1,53 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * Header file for the IRQ RPC implementation.
+ *
+ * @addtogroup IRQ_SVC
+ * @{
+ */
+
+#ifndef _SC_IRQ_RPC_H
+#define _SC_IRQ_RPC_H
+
+/* Includes */
+
+/* Defines */
+
+/* Types */
+
+/*!
+ * This type is used to indicate RPC IRQ function calls.
+ */
+typedef enum irq_func_e {
+ IRQ_FUNC_UNKNOWN = 0, /* Unknown function */
+ IRQ_FUNC_ENABLE = 1, /* Index for irq_enable() RPC call */
+ IRQ_FUNC_STATUS = 2, /* Index for irq_status() RPC call */
+} irq_func_t;
+
+/* Functions */
+
+/*!
+ * This function dispatches an incoming IRQ RPC request.
+ *
+ * @param[in] caller_pt caller partition
+ * @param[in] msg pointer to RPC message
+ */
+void irq_dispatch(sc_rm_pt_t caller_pt, sc_rpc_msg_t *msg);
+
+/*!
+ * This function translates and dispatches an IRQ RPC request.
+ *
+ * @param[in] ipc IPC handle
+ * @param[in] msg pointer to RPC message
+ */
+void irq_xlate(sc_ipc_t ipc, sc_rpc_msg_t *msg);
+
+#endif /* _SC_IRQ_RPC_H */
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/irq/rpc_clnt.c b/drivers/soc/imx/sc/svc/irq/rpc_clnt.c
new file mode 100644
index 000000000000..779be383aea3
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/irq/rpc_clnt.c
@@ -0,0 +1,74 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * File containing client-side RPC functions for the IRQ service. These
+ * functions are ported to clients that communicate to the SC.
+ *
+ * @addtogroup IRQ_SVC
+ * @{
+ */
+
+/* Includes */
+
+#include <soc/imx8/sc/types.h>
+#include <soc/imx8/sc/svc/rm/api.h>
+#include <soc/imx8/sc/svc/irq/api.h>
+#include "../../main/rpc.h"
+#include "rpc.h"
+
+/* Local Defines */
+
+/* Local Types */
+
+/* Local Functions */
+
+sc_err_t sc_irq_enable(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_irq_group_t group, uint32_t mask, bool enable)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_IRQ;
+ RPC_FUNC(&msg) = (uint8_t)IRQ_FUNC_ENABLE;
+ RPC_U32(&msg, 0) = mask;
+ RPC_U16(&msg, 4) = resource;
+ RPC_U8(&msg, 6) = group;
+ RPC_U8(&msg, 7) = (uint8_t)enable;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_irq_status(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_irq_group_t group, uint32_t *status)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_IRQ;
+ RPC_FUNC(&msg) = (uint8_t)IRQ_FUNC_STATUS;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = group;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (status != NULL) {
+ *status = RPC_U32(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/misc/rpc.h b/drivers/soc/imx/sc/svc/misc/rpc.h
new file mode 100644
index 000000000000..087b6b9f6dea
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/misc/rpc.h
@@ -0,0 +1,70 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * Header file for the MISC RPC implementation.
+ *
+ * @addtogroup MISC_SVC
+ * @{
+ */
+
+#ifndef _SC_MISC_RPC_H
+#define _SC_MISC_RPC_H
+
+/* Includes */
+
+/* Defines */
+
+/* Types */
+
+/*!
+ * This type is used to indicate RPC MISC function calls.
+ */
+typedef enum misc_func_e {
+ MISC_FUNC_UNKNOWN = 0, /* Unknown function */
+ MISC_FUNC_SET_CONTROL = 1, /* Index for misc_set_control() RPC call */
+ MISC_FUNC_GET_CONTROL = 2, /* Index for misc_get_control() RPC call */
+ MISC_FUNC_SET_MAX_DMA_GROUP = 4, /* Index for misc_set_max_dma_group() RPC call */
+ MISC_FUNC_SET_DMA_GROUP = 5, /* Index for misc_set_dma_group() RPC call */
+ MISC_FUNC_SECO_IMAGE_LOAD = 8, /* Index for misc_seco_image_load() RPC call */
+ MISC_FUNC_SECO_AUTHENTICATE = 9, /* Index for misc_seco_authenticate() RPC call */
+ MISC_FUNC_DEBUG_OUT = 10, /* Index for misc_debug_out() RPC call */
+ MISC_FUNC_WAVEFORM_CAPTURE = 6, /* Index for misc_waveform_capture() RPC call */
+ MISC_FUNC_BUILD_INFO = 15, /* Index for misc_build_info() RPC call */
+ MISC_FUNC_UNIQUE_ID = 19, /* Index for misc_unique_id() RPC call */
+ MISC_FUNC_SET_ARI = 3, /* Index for misc_set_ari() RPC call */
+ MISC_FUNC_BOOT_STATUS = 7, /* Index for misc_boot_status() RPC call */
+ MISC_FUNC_BOOT_DONE = 14, /* Index for misc_boot_done() RPC call */
+ MISC_FUNC_OTP_FUSE_READ = 11, /* Index for misc_otp_fuse_read() RPC call */
+ MISC_FUNC_OTP_FUSE_WRITE = 17, /* Index for misc_otp_fuse_write() RPC call */
+ MISC_FUNC_SET_TEMP = 12, /* Index for misc_set_temp() RPC call */
+ MISC_FUNC_GET_TEMP = 13, /* Index for misc_get_temp() RPC call */
+ MISC_FUNC_GET_BOOT_DEV = 16, /* Index for misc_get_boot_dev() RPC call */
+ MISC_FUNC_GET_BUTTON_STATUS = 18, /* Index for misc_get_button_status() RPC call */
+} misc_func_t;
+
+/* Functions */
+
+/*!
+ * This function dispatches an incoming MISC RPC request.
+ *
+ * @param[in] caller_pt caller partition
+ * @param[in] msg pointer to RPC message
+ */
+void misc_dispatch(sc_rm_pt_t caller_pt, sc_rpc_msg_t *msg);
+
+/*!
+ * This function translates and dispatches an MISC RPC request.
+ *
+ * @param[in] ipc IPC handle
+ * @param[in] msg pointer to RPC message
+ */
+void misc_xlate(sc_ipc_t ipc, sc_rpc_msg_t *msg);
+
+#endif /* _SC_MISC_RPC_H */
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/misc/rpc_clnt.c b/drivers/soc/imx/sc/svc/misc/rpc_clnt.c
new file mode 100644
index 000000000000..e1f588c52b5c
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/misc/rpc_clnt.c
@@ -0,0 +1,405 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * File containing client-side RPC functions for the MISC service. These
+ * functions are ported to clients that communicate to the SC.
+ *
+ * @addtogroup MISC_SVC
+ * @{
+ */
+
+/* Includes */
+
+#include <soc/imx8/sc/types.h>
+#include <soc/imx8/sc/svc/rm/api.h>
+#include <soc/imx8/sc/svc/misc/api.h>
+#include "../../main/rpc.h"
+#include "rpc.h"
+
+/* Local Defines */
+
+/* Local Types */
+
+/* Local Functions */
+
+sc_err_t sc_misc_set_control(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_ctrl_t ctrl, uint32_t val)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_SET_CONTROL;
+ RPC_U32(&msg, 0) = ctrl;
+ RPC_U32(&msg, 4) = val;
+ RPC_U16(&msg, 8) = resource;
+ RPC_SIZE(&msg) = 4;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_misc_get_control(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_ctrl_t ctrl, uint32_t *val)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_GET_CONTROL;
+ RPC_U32(&msg, 0) = ctrl;
+ RPC_U16(&msg, 4) = resource;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (val != NULL) {
+ *val = RPC_U32(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_misc_set_max_dma_group(sc_ipc_t ipc, sc_rm_pt_t pt,
+ sc_misc_dma_group_t max)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_SET_MAX_DMA_GROUP;
+ RPC_U8(&msg, 0) = pt;
+ RPC_U8(&msg, 1) = max;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_misc_set_dma_group(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_misc_dma_group_t group)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_SET_DMA_GROUP;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = group;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_misc_seco_image_load(sc_ipc_t ipc, uint32_t addr_src,
+ uint32_t addr_dst, uint32_t len, bool fw)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_SECO_IMAGE_LOAD;
+ RPC_U32(&msg, 0) = addr_src;
+ RPC_U32(&msg, 4) = addr_dst;
+ RPC_U32(&msg, 8) = len;
+ RPC_U8(&msg, 12) = (uint8_t)fw;
+ RPC_SIZE(&msg) = 5;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_misc_seco_authenticate(sc_ipc_t ipc,
+ sc_misc_seco_auth_cmd_t cmd,
+ uint32_t addr_meta)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_SECO_AUTHENTICATE;
+ RPC_U32(&msg, 0) = addr_meta;
+ RPC_U8(&msg, 4) = cmd;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+void sc_misc_debug_out(sc_ipc_t ipc, uint8_t ch)
+{
+ sc_rpc_msg_t msg;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_DEBUG_OUT;
+ RPC_U8(&msg, 0) = ch;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ return;
+}
+
+sc_err_t sc_misc_waveform_capture(sc_ipc_t ipc, bool enable)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_WAVEFORM_CAPTURE;
+ RPC_U8(&msg, 0) = (uint8_t)enable;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+void sc_misc_build_info(sc_ipc_t ipc, uint32_t *build, uint32_t *commit)
+{
+ sc_rpc_msg_t msg;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_BUILD_INFO;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (build != NULL) {
+ *build = RPC_U32(&msg, 0);
+ }
+
+ if (commit != NULL) {
+ *commit = RPC_U32(&msg, 4);
+ }
+
+ return;
+}
+
+void sc_misc_unique_id(sc_ipc_t ipc, uint32_t *id_l, uint32_t *id_h)
+{
+ sc_rpc_msg_t msg;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_UNIQUE_ID;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (id_l != NULL) {
+ *id_l = RPC_U32(&msg, 0);
+ }
+
+ if (id_h != NULL) {
+ *id_h = RPC_U32(&msg, 4);
+ }
+
+ return;
+}
+
+sc_err_t sc_misc_set_ari(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_rsrc_t resource_mst, uint16_t ari, bool enable)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_SET_ARI;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U16(&msg, 2) = resource_mst;
+ RPC_U16(&msg, 4) = ari;
+ RPC_U8(&msg, 6) = (uint8_t)enable;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+void sc_misc_boot_status(sc_ipc_t ipc, sc_misc_boot_status_t status)
+{
+ sc_rpc_msg_t msg;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_BOOT_STATUS;
+ RPC_U8(&msg, 0) = status;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, true);
+
+ return;
+}
+
+sc_err_t sc_misc_boot_done(sc_ipc_t ipc, sc_rsrc_t cpu)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_BOOT_DONE;
+ RPC_U16(&msg, 0) = cpu;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_misc_otp_fuse_read(sc_ipc_t ipc, uint32_t word, uint32_t *val)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_OTP_FUSE_READ;
+ RPC_U32(&msg, 0) = word;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (val != NULL) {
+ *val = RPC_U32(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_misc_otp_fuse_write(sc_ipc_t ipc, uint32_t word, uint32_t val)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_OTP_FUSE_WRITE;
+ RPC_U32(&msg, 0) = word;
+ RPC_U32(&msg, 4) = val;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_misc_set_temp(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_misc_temp_t temp, int16_t celsius, int8_t tenths)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_SET_TEMP;
+ RPC_U16(&msg, 0) = resource;
+ RPC_I16(&msg, 2) = celsius;
+ RPC_U8(&msg, 4) = temp;
+ RPC_I8(&msg, 5) = tenths;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_misc_get_temp(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_misc_temp_t temp, int16_t * celsius,
+ int8_t * tenths)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_GET_TEMP;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = temp;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (celsius != NULL) {
+ *celsius = RPC_I16(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ if (tenths != NULL) {
+ *tenths = RPC_I8(&msg, 2);
+ }
+
+ return (sc_err_t)result;
+}
+
+void sc_misc_get_boot_dev(sc_ipc_t ipc, sc_rsrc_t *dev)
+{
+ sc_rpc_msg_t msg;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_GET_BOOT_DEV;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (dev != NULL) {
+ *dev = RPC_U16(&msg, 0);
+ }
+
+ return;
+}
+
+void sc_misc_get_button_status(sc_ipc_t ipc, bool *status)
+{
+ sc_rpc_msg_t msg;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_MISC;
+ RPC_FUNC(&msg) = (uint8_t)MISC_FUNC_GET_BUTTON_STATUS;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (status != NULL) {
+ *status = RPC_U8(&msg, 0);
+ }
+
+ return;
+}
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/pad/rpc.h b/drivers/soc/imx/sc/svc/pad/rpc.h
new file mode 100644
index 000000000000..ee8fe3b42af2
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/pad/rpc.h
@@ -0,0 +1,67 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * Header file for the PAD RPC implementation.
+ *
+ * @addtogroup PAD_SVC
+ * @{
+ */
+
+#ifndef _SC_PAD_RPC_H
+#define _SC_PAD_RPC_H
+
+/* Includes */
+
+/* Defines */
+
+/* Types */
+
+/*!
+ * This type is used to indicate RPC PAD function calls.
+ */
+typedef enum pad_func_e {
+ PAD_FUNC_UNKNOWN = 0, /* Unknown function */
+ PAD_FUNC_SET_MUX = 1, /* Index for pad_set_mux() RPC call */
+ PAD_FUNC_GET_MUX = 6, /* Index for pad_get_mux() RPC call */
+ PAD_FUNC_SET_GP = 2, /* Index for pad_set_gp() RPC call */
+ PAD_FUNC_GET_GP = 7, /* Index for pad_get_gp() RPC call */
+ PAD_FUNC_SET_WAKEUP = 4, /* Index for pad_set_wakeup() RPC call */
+ PAD_FUNC_GET_WAKEUP = 9, /* Index for pad_get_wakeup() RPC call */
+ PAD_FUNC_SET_ALL = 5, /* Index for pad_set_all() RPC call */
+ PAD_FUNC_GET_ALL = 10, /* Index for pad_get_all() RPC call */
+ PAD_FUNC_SET = 15, /* Index for pad_set() RPC call */
+ PAD_FUNC_GET = 16, /* Index for pad_get() RPC call */
+ PAD_FUNC_SET_GP_28FDSOI = 11, /* Index for pad_set_gp_28fdsoi() RPC call */
+ PAD_FUNC_GET_GP_28FDSOI = 12, /* Index for pad_get_gp_28fdsoi() RPC call */
+ PAD_FUNC_SET_GP_28FDSOI_HSIC = 3, /* Index for pad_set_gp_28fdsoi_hsic() RPC call */
+ PAD_FUNC_GET_GP_28FDSOI_HSIC = 8, /* Index for pad_get_gp_28fdsoi_hsic() RPC call */
+ PAD_FUNC_SET_GP_28FDSOI_COMP = 13, /* Index for pad_set_gp_28fdsoi_comp() RPC call */
+ PAD_FUNC_GET_GP_28FDSOI_COMP = 14, /* Index for pad_get_gp_28fdsoi_comp() RPC call */
+} pad_func_t;
+
+/* Functions */
+
+/*!
+ * This function dispatches an incoming PAD RPC request.
+ *
+ * @param[in] caller_pt caller partition
+ * @param[in] msg pointer to RPC message
+ */
+void pad_dispatch(sc_rm_pt_t caller_pt, sc_rpc_msg_t *msg);
+
+/*!
+ * This function translates and dispatches an PAD RPC request.
+ *
+ * @param[in] ipc IPC handle
+ * @param[in] msg pointer to RPC message
+ */
+void pad_xlate(sc_ipc_t ipc, sc_rpc_msg_t *msg);
+
+#endif /* _SC_PAD_RPC_H */
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/pad/rpc_clnt.c b/drivers/soc/imx/sc/svc/pad/rpc_clnt.c
new file mode 100644
index 000000000000..90fb3904ca7b
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/pad/rpc_clnt.c
@@ -0,0 +1,453 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * File containing client-side RPC functions for the PAD service. These
+ * functions are ported to clients that communicate to the SC.
+ *
+ * @addtogroup PAD_SVC
+ * @{
+ */
+
+/* Includes */
+
+#include <soc/imx8/sc/types.h>
+#include <soc/imx8/sc/svc/rm/api.h>
+#include <soc/imx8/sc/svc/pad/api.h>
+#include "../../main/rpc.h"
+#include "rpc.h"
+
+/* Local Defines */
+
+/* Local Types */
+
+/* Local Functions */
+
+sc_err_t sc_pad_set_mux(sc_ipc_t ipc, sc_pad_t pad,
+ uint8_t mux, sc_pad_config_t config, sc_pad_iso_t iso)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_SET_MUX;
+ RPC_U16(&msg, 0) = pad;
+ RPC_U8(&msg, 2) = mux;
+ RPC_U8(&msg, 3) = config;
+ RPC_U8(&msg, 4) = iso;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_get_mux(sc_ipc_t ipc, sc_pad_t pad,
+ uint8_t *mux, sc_pad_config_t *config,
+ sc_pad_iso_t *iso)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_GET_MUX;
+ RPC_U16(&msg, 0) = pad;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (mux != NULL) {
+ *mux = RPC_U8(&msg, 0);
+ }
+
+ if (config != NULL) {
+ *config = RPC_U8(&msg, 1);
+ }
+
+ if (iso != NULL) {
+ *iso = RPC_U8(&msg, 2);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_set_gp(sc_ipc_t ipc, sc_pad_t pad, uint32_t ctrl)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_SET_GP;
+ RPC_U32(&msg, 0) = ctrl;
+ RPC_U16(&msg, 4) = pad;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_get_gp(sc_ipc_t ipc, sc_pad_t pad, uint32_t *ctrl)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_GET_GP;
+ RPC_U16(&msg, 0) = pad;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (ctrl != NULL) {
+ *ctrl = RPC_U32(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_set_wakeup(sc_ipc_t ipc, sc_pad_t pad, sc_pad_wakeup_t wakeup)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_SET_WAKEUP;
+ RPC_U16(&msg, 0) = pad;
+ RPC_U8(&msg, 2) = wakeup;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_get_wakeup(sc_ipc_t ipc, sc_pad_t pad, sc_pad_wakeup_t *wakeup)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_GET_WAKEUP;
+ RPC_U16(&msg, 0) = pad;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (wakeup != NULL) {
+ *wakeup = RPC_U8(&msg, 0);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_set_all(sc_ipc_t ipc, sc_pad_t pad, uint8_t mux,
+ sc_pad_config_t config, sc_pad_iso_t iso, uint32_t ctrl,
+ sc_pad_wakeup_t wakeup)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_SET_ALL;
+ RPC_U32(&msg, 0) = ctrl;
+ RPC_U16(&msg, 4) = pad;
+ RPC_U8(&msg, 6) = mux;
+ RPC_U8(&msg, 7) = config;
+ RPC_U8(&msg, 8) = iso;
+ RPC_U8(&msg, 9) = wakeup;
+ RPC_SIZE(&msg) = 4;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_get_all(sc_ipc_t ipc, sc_pad_t pad, uint8_t *mux,
+ sc_pad_config_t *config, sc_pad_iso_t *iso,
+ uint32_t *ctrl, sc_pad_wakeup_t *wakeup)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_GET_ALL;
+ RPC_U16(&msg, 0) = pad;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (ctrl != NULL) {
+ *ctrl = RPC_U32(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ if (mux != NULL) {
+ *mux = RPC_U8(&msg, 4);
+ }
+
+ if (config != NULL) {
+ *config = RPC_U8(&msg, 5);
+ }
+
+ if (iso != NULL) {
+ *iso = RPC_U8(&msg, 6);
+ }
+
+ if (wakeup != NULL) {
+ *wakeup = RPC_U8(&msg, 7);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_set(sc_ipc_t ipc, sc_pad_t pad, uint32_t val)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_SET;
+ RPC_U32(&msg, 0) = val;
+ RPC_U16(&msg, 4) = pad;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_get(sc_ipc_t ipc, sc_pad_t pad, uint32_t *val)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_GET;
+ RPC_U16(&msg, 0) = pad;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (val != NULL) {
+ *val = RPC_U32(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_set_gp_28fdsoi(sc_ipc_t ipc, sc_pad_t pad,
+ sc_pad_28fdsoi_dse_t dse, sc_pad_28fdsoi_ps_t ps)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_SET_GP_28FDSOI;
+ RPC_U16(&msg, 0) = pad;
+ RPC_U8(&msg, 2) = dse;
+ RPC_U8(&msg, 3) = ps;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_get_gp_28fdsoi(sc_ipc_t ipc, sc_pad_t pad,
+ sc_pad_28fdsoi_dse_t *dse,
+ sc_pad_28fdsoi_ps_t *ps)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_GET_GP_28FDSOI;
+ RPC_U16(&msg, 0) = pad;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (dse != NULL) {
+ *dse = RPC_U8(&msg, 0);
+ }
+
+ if (ps != NULL) {
+ *ps = RPC_U8(&msg, 1);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_set_gp_28fdsoi_hsic(sc_ipc_t ipc, sc_pad_t pad,
+ sc_pad_28fdsoi_dse_t dse, bool hys,
+ sc_pad_28fdsoi_pus_t pus, bool pke,
+ bool pue)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_SET_GP_28FDSOI_HSIC;
+ RPC_U16(&msg, 0) = pad;
+ RPC_U8(&msg, 2) = dse;
+ RPC_U8(&msg, 3) = pus;
+ RPC_U8(&msg, 4) = (uint8_t)hys;
+ RPC_U8(&msg, 5) = (uint8_t)pke;
+ RPC_U8(&msg, 6) = (uint8_t)pue;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_get_gp_28fdsoi_hsic(sc_ipc_t ipc, sc_pad_t pad,
+ sc_pad_28fdsoi_dse_t *dse, bool *hys,
+ sc_pad_28fdsoi_pus_t *pus, bool *pke,
+ bool *pue)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_GET_GP_28FDSOI_HSIC;
+ RPC_U16(&msg, 0) = pad;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (dse != NULL) {
+ *dse = RPC_U8(&msg, 0);
+ }
+
+ if (pus != NULL) {
+ *pus = RPC_U8(&msg, 1);
+ }
+
+ if (hys != NULL) {
+ *hys = RPC_U8(&msg, 2);
+ }
+
+ if (pke != NULL) {
+ *pke = RPC_U8(&msg, 3);
+ }
+
+ if (pue != NULL) {
+ *pue = RPC_U8(&msg, 4);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_set_gp_28fdsoi_comp(sc_ipc_t ipc, sc_pad_t pad,
+ uint8_t compen, bool fastfrz,
+ uint8_t rasrcp, uint8_t rasrcn,
+ bool nasrc_sel, bool psw_ovr)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_SET_GP_28FDSOI_COMP;
+ RPC_U16(&msg, 0) = pad;
+ RPC_U8(&msg, 2) = compen;
+ RPC_U8(&msg, 3) = rasrcp;
+ RPC_U8(&msg, 4) = rasrcn;
+ RPC_U8(&msg, 5) = (uint8_t)fastfrz;
+ RPC_U8(&msg, 6) = (uint8_t)nasrc_sel;
+ RPC_U8(&msg, 7) = (uint8_t)psw_ovr;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pad_get_gp_28fdsoi_comp(sc_ipc_t ipc, sc_pad_t pad,
+ uint8_t *compen, bool *fastfrz,
+ uint8_t *rasrcp, uint8_t *rasrcn,
+ bool *nasrc_sel, bool *compok,
+ uint8_t *nasrc, bool *psw_ovr)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PAD;
+ RPC_FUNC(&msg) = (uint8_t)PAD_FUNC_GET_GP_28FDSOI_COMP;
+ RPC_U16(&msg, 0) = pad;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (compen != NULL) {
+ *compen = RPC_U8(&msg, 0);
+ }
+
+ if (rasrcp != NULL) {
+ *rasrcp = RPC_U8(&msg, 1);
+ }
+
+ if (rasrcn != NULL) {
+ *rasrcn = RPC_U8(&msg, 2);
+ }
+
+ if (nasrc != NULL) {
+ *nasrc = RPC_U8(&msg, 3);
+ }
+
+ if (fastfrz != NULL) {
+ *fastfrz = RPC_U8(&msg, 4);
+ }
+
+ if (nasrc_sel != NULL) {
+ *nasrc_sel = RPC_U8(&msg, 5);
+ }
+
+ if (compok != NULL) {
+ *compok = RPC_U8(&msg, 6);
+ }
+
+ if (psw_ovr != NULL) {
+ *psw_ovr = RPC_U8(&msg, 7);
+ }
+
+ return (sc_err_t)result;
+}
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/pm/rpc.h b/drivers/soc/imx/sc/svc/pm/rpc.h
new file mode 100644
index 000000000000..e83db74d20bd
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/pm/rpc.h
@@ -0,0 +1,70 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * Header file for the PM RPC implementation.
+ *
+ * @addtogroup PM_SVC
+ * @{
+ */
+
+#ifndef _SC_PM_RPC_H
+#define _SC_PM_RPC_H
+
+/* Includes */
+
+/* Defines */
+
+/* Types */
+
+/*!
+ * This type is used to indicate RPC PM function calls.
+ */
+typedef enum pm_func_e {
+ PM_FUNC_UNKNOWN = 0, /* Unknown function */
+ PM_FUNC_SET_SYS_POWER_MODE = 19, /* Index for pm_set_sys_power_mode() RPC call */
+ PM_FUNC_SET_PARTITION_POWER_MODE = 1, /* Index for pm_set_partition_power_mode() RPC call */
+ PM_FUNC_GET_SYS_POWER_MODE = 2, /* Index for pm_get_sys_power_mode() RPC call */
+ PM_FUNC_SET_RESOURCE_POWER_MODE = 3, /* Index for pm_set_resource_power_mode() RPC call */
+ PM_FUNC_GET_RESOURCE_POWER_MODE = 4, /* Index for pm_get_resource_power_mode() RPC call */
+ PM_FUNC_REQ_LOW_POWER_MODE = 16, /* Index for pm_req_low_power_mode() RPC call */
+ PM_FUNC_SET_CPU_RESUME_ADDR = 17, /* Index for pm_set_cpu_resume_addr() RPC call */
+ PM_FUNC_REQ_SYS_IF_POWER_MODE = 18, /* Index for pm_req_sys_if_power_mode() RPC call */
+ PM_FUNC_SET_CLOCK_RATE = 5, /* Index for pm_set_clock_rate() RPC call */
+ PM_FUNC_GET_CLOCK_RATE = 6, /* Index for pm_get_clock_rate() RPC call */
+ PM_FUNC_CLOCK_ENABLE = 7, /* Index for pm_clock_enable() RPC call */
+ PM_FUNC_SET_CLOCK_PARENT = 14, /* Index for pm_set_clock_parent() RPC call */
+ PM_FUNC_GET_CLOCK_PARENT = 15, /* Index for pm_get_clock_parent() RPC call */
+ PM_FUNC_RESET = 13, /* Index for pm_reset() RPC call */
+ PM_FUNC_RESET_REASON = 10, /* Index for pm_reset_reason() RPC call */
+ PM_FUNC_BOOT = 8, /* Index for pm_boot() RPC call */
+ PM_FUNC_REBOOT = 9, /* Index for pm_reboot() RPC call */
+ PM_FUNC_REBOOT_PARTITION = 12, /* Index for pm_reboot_partition() RPC call */
+ PM_FUNC_CPU_START = 11, /* Index for pm_cpu_start() RPC call */
+} pm_func_t;
+
+/* Functions */
+
+/*!
+ * This function dispatches an incoming PM RPC request.
+ *
+ * @param[in] caller_pt caller partition
+ * @param[in] msg pointer to RPC message
+ */
+void pm_dispatch(sc_rm_pt_t caller_pt, sc_rpc_msg_t *msg);
+
+/*!
+ * This function translates and dispatches an PM RPC request.
+ *
+ * @param[in] ipc IPC handle
+ * @param[in] msg pointer to RPC message
+ */
+void pm_xlate(sc_ipc_t ipc, sc_rpc_msg_t *msg);
+
+#endif /* _SC_PM_RPC_H */
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/pm/rpc_clnt.c b/drivers/soc/imx/sc/svc/pm/rpc_clnt.c
new file mode 100644
index 000000000000..b4b651e91ad5
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/pm/rpc_clnt.c
@@ -0,0 +1,415 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * File containing client-side RPC functions for the PM service. These
+ * functions are ported to clients that communicate to the SC.
+ *
+ * @addtogroup PM_SVC
+ * @{
+ */
+
+/* Includes */
+
+#include <soc/imx8/sc/types.h>
+#include <soc/imx8/sc/svc/rm/api.h>
+#include <soc/imx8/sc/svc/pm/api.h>
+#include "../../main/rpc.h"
+#include "rpc.h"
+
+/* Local Defines */
+
+/* Local Types */
+
+/* Local Functions */
+
+sc_err_t sc_pm_set_sys_power_mode(sc_ipc_t ipc, sc_pm_power_mode_t mode)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_SET_SYS_POWER_MODE;
+ RPC_U8(&msg, 0) = mode;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_set_partition_power_mode(sc_ipc_t ipc, sc_rm_pt_t pt,
+ sc_pm_power_mode_t mode)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_SET_PARTITION_POWER_MODE;
+ RPC_U8(&msg, 0) = pt;
+ RPC_U8(&msg, 1) = mode;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_get_sys_power_mode(sc_ipc_t ipc, sc_rm_pt_t pt,
+ sc_pm_power_mode_t *mode)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_GET_SYS_POWER_MODE;
+ RPC_U8(&msg, 0) = pt;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (mode != NULL) {
+ *mode = RPC_U8(&msg, 0);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_set_resource_power_mode(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_pm_power_mode_t mode)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_SET_RESOURCE_POWER_MODE;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = mode;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_get_resource_power_mode(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_pm_power_mode_t *mode)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_GET_RESOURCE_POWER_MODE;
+ RPC_U16(&msg, 0) = resource;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (mode != NULL) {
+ *mode = RPC_U8(&msg, 0);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_req_low_power_mode(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_pm_power_mode_t mode)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_REQ_LOW_POWER_MODE;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = mode;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_set_cpu_resume_addr(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_faddr_t address)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_SET_CPU_RESUME_ADDR;
+ RPC_U32(&msg, 0) = (uint32_t)(address >> 32u);
+ RPC_U32(&msg, 4) = (uint32_t)address;
+ RPC_U16(&msg, 8) = resource;
+ RPC_SIZE(&msg) = 4;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_req_sys_if_power_mode(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_pm_sys_if_t sys_if,
+ sc_pm_power_mode_t hpm,
+ sc_pm_power_mode_t lpm)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_REQ_SYS_IF_POWER_MODE;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = sys_if;
+ RPC_U8(&msg, 3) = hpm;
+ RPC_U8(&msg, 4) = lpm;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_set_clock_rate(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_pm_clk_t clk, sc_pm_clock_rate_t *rate)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_SET_CLOCK_RATE;
+ RPC_U32(&msg, 0) = *rate;
+ RPC_U16(&msg, 4) = resource;
+ RPC_U8(&msg, 6) = clk;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ *rate = RPC_U32(&msg, 0);
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_get_clock_rate(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_pm_clk_t clk, sc_pm_clock_rate_t *rate)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_GET_CLOCK_RATE;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = clk;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (rate != NULL) {
+ *rate = RPC_U32(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_clock_enable(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_pm_clk_t clk, bool enable, bool autog)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_CLOCK_ENABLE;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = clk;
+ RPC_U8(&msg, 3) = (uint8_t)enable;
+ RPC_U8(&msg, 4) = (uint8_t)autog;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_set_clock_parent(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_pm_clk_t clk, sc_pm_clk_parent_t parent)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_SET_CLOCK_PARENT;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = clk;
+ RPC_U8(&msg, 3) = parent;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_get_clock_parent(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_pm_clk_t clk, sc_pm_clk_parent_t * parent)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_GET_CLOCK_PARENT;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = clk;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (parent != NULL) {
+ *parent = RPC_U8(&msg, 0);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_reset(sc_ipc_t ipc, sc_pm_reset_type_t type)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_RESET;
+ RPC_U8(&msg, 0) = type;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_reset_reason(sc_ipc_t ipc, sc_pm_reset_reason_t *reason)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_RESET_REASON;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (reason != NULL) {
+ *reason = RPC_U8(&msg, 0);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_boot(sc_ipc_t ipc, sc_rm_pt_t pt,
+ sc_rsrc_t resource_cpu, sc_faddr_t boot_addr,
+ sc_rsrc_t resource_mu, sc_rsrc_t resource_dev)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_BOOT;
+ RPC_U32(&msg, 0) = (uint32_t)(boot_addr >> 32u);
+ RPC_U32(&msg, 4) = (uint32_t)boot_addr;
+ RPC_U16(&msg, 8) = resource_cpu;
+ RPC_U16(&msg, 10) = resource_mu;
+ RPC_U16(&msg, 12) = resource_dev;
+ RPC_U8(&msg, 14) = pt;
+ RPC_SIZE(&msg) = 5;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+void sc_pm_reboot(sc_ipc_t ipc, sc_pm_reset_type_t type)
+{
+ sc_rpc_msg_t msg;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_REBOOT;
+ RPC_U8(&msg, 0) = type;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, true);
+
+ return;
+}
+
+sc_err_t sc_pm_reboot_partition(sc_ipc_t ipc, sc_rm_pt_t pt,
+ sc_pm_reset_type_t type)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_REBOOT_PARTITION;
+ RPC_U8(&msg, 0) = pt;
+ RPC_U8(&msg, 1) = type;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_pm_cpu_start(sc_ipc_t ipc, sc_rsrc_t resource, bool enable,
+ sc_faddr_t address)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_PM;
+ RPC_FUNC(&msg) = (uint8_t)PM_FUNC_CPU_START;
+ RPC_U32(&msg, 0) = (uint32_t)(address >> 32u);
+ RPC_U32(&msg, 4) = (uint32_t)address;
+ RPC_U16(&msg, 8) = resource;
+ RPC_U8(&msg, 10) = (uint8_t)enable;
+ RPC_SIZE(&msg) = 4;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/rm/rpc.h b/drivers/soc/imx/sc/svc/rm/rpc.h
new file mode 100644
index 000000000000..457b01860ae5
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/rm/rpc.h
@@ -0,0 +1,82 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * Header file for the RM RPC implementation.
+ *
+ * @addtogroup RM_SVC
+ * @{
+ */
+
+#ifndef _SC_RM_RPC_H
+#define _SC_RM_RPC_H
+
+/* Includes */
+
+/* Defines */
+
+/* Types */
+
+/*!
+ * This type is used to indicate RPC RM function calls.
+ */
+typedef enum rm_func_e {
+ RM_FUNC_UNKNOWN = 0, /* Unknown function */
+ RM_FUNC_PARTITION_ALLOC = 1, /* Index for rm_partition_alloc() RPC call */
+ RM_FUNC_SET_CONFIDENTIAL = 31, /* Index for rm_set_confidential() RPC call */
+ RM_FUNC_PARTITION_FREE = 2, /* Index for rm_partition_free() RPC call */
+ RM_FUNC_GET_DID = 26, /* Index for rm_get_did() RPC call */
+ RM_FUNC_PARTITION_STATIC = 3, /* Index for rm_partition_static() RPC call */
+ RM_FUNC_PARTITION_LOCK = 4, /* Index for rm_partition_lock() RPC call */
+ RM_FUNC_GET_PARTITION = 5, /* Index for rm_get_partition() RPC call */
+ RM_FUNC_SET_PARENT = 6, /* Index for rm_set_parent() RPC call */
+ RM_FUNC_MOVE_ALL = 7, /* Index for rm_move_all() RPC call */
+ RM_FUNC_ASSIGN_RESOURCE = 8, /* Index for rm_assign_resource() RPC call */
+ RM_FUNC_SET_RESOURCE_MOVABLE = 9, /* Index for rm_set_resource_movable() RPC call */
+ RM_FUNC_SET_SUBSYS_RSRC_MOVABLE = 28, /* Index for rm_set_subsys_rsrc_movable() RPC call */
+ RM_FUNC_SET_MASTER_ATTRIBUTES = 10, /* Index for rm_set_master_attributes() RPC call */
+ RM_FUNC_SET_MASTER_SID = 11, /* Index for rm_set_master_sid() RPC call */
+ RM_FUNC_SET_PERIPHERAL_PERMISSIONS = 12, /* Index for rm_set_peripheral_permissions() RPC call */
+ RM_FUNC_IS_RESOURCE_OWNED = 13, /* Index for rm_is_resource_owned() RPC call */
+ RM_FUNC_IS_RESOURCE_MASTER = 14, /* Index for rm_is_resource_master() RPC call */
+ RM_FUNC_IS_RESOURCE_PERIPHERAL = 15, /* Index for rm_is_resource_peripheral() RPC call */
+ RM_FUNC_GET_RESOURCE_INFO = 16, /* Index for rm_get_resource_info() RPC call */
+ RM_FUNC_MEMREG_ALLOC = 17, /* Index for rm_memreg_alloc() RPC call */
+ RM_FUNC_MEMREG_SPLIT = 29, /* Index for rm_memreg_split() RPC call */
+ RM_FUNC_MEMREG_FREE = 18, /* Index for rm_memreg_free() RPC call */
+ RM_FUNC_FIND_MEMREG = 30, /* Index for rm_find_memreg() RPC call */
+ RM_FUNC_ASSIGN_MEMREG = 19, /* Index for rm_assign_memreg() RPC call */
+ RM_FUNC_SET_MEMREG_PERMISSIONS = 20, /* Index for rm_set_memreg_permissions() RPC call */
+ RM_FUNC_IS_MEMREG_OWNED = 21, /* Index for rm_is_memreg_owned() RPC call */
+ RM_FUNC_GET_MEMREG_INFO = 22, /* Index for rm_get_memreg_info() RPC call */
+ RM_FUNC_ASSIGN_PAD = 23, /* Index for rm_assign_pad() RPC call */
+ RM_FUNC_SET_PAD_MOVABLE = 24, /* Index for rm_set_pad_movable() RPC call */
+ RM_FUNC_IS_PAD_OWNED = 25, /* Index for rm_is_pad_owned() RPC call */
+ RM_FUNC_DUMP = 27, /* Index for rm_dump() RPC call */
+} rm_func_t;
+
+/* Functions */
+
+/*!
+ * This function dispatches an incoming RM RPC request.
+ *
+ * @param[in] caller_pt caller partition
+ * @param[in] msg pointer to RPC message
+ */
+void rm_dispatch(sc_rm_pt_t caller_pt, sc_rpc_msg_t *msg);
+
+/*!
+ * This function translates and dispatches an RM RPC request.
+ *
+ * @param[in] ipc IPC handle
+ * @param[in] msg pointer to RPC message
+ */
+void rm_xlate(sc_ipc_t ipc, sc_rpc_msg_t *msg);
+
+#endif /* _SC_RM_RPC_H */
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/rm/rpc_clnt.c b/drivers/soc/imx/sc/svc/rm/rpc_clnt.c
new file mode 100644
index 000000000000..a9bb6ba42c15
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/rm/rpc_clnt.c
@@ -0,0 +1,637 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * File containing client-side RPC functions for the RM service. These
+ * functions are ported to clients that communicate to the SC.
+ *
+ * @addtogroup RM_SVC
+ * @{
+ */
+
+/* Includes */
+
+#include <soc/imx8/sc/types.h>
+#include <soc/imx8/sc/svc/rm/api.h>
+#include "../../main/rpc.h"
+#include "rpc.h"
+
+/* Local Defines */
+
+/* Local Types */
+
+/* Local Functions */
+
+sc_err_t sc_rm_partition_alloc(sc_ipc_t ipc, sc_rm_pt_t *pt, bool secure,
+ bool isolated, bool restricted, bool grant,
+ bool coherent)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_PARTITION_ALLOC;
+ RPC_U8(&msg, 0) = (uint8_t)secure;
+ RPC_U8(&msg, 1) = (uint8_t)isolated;
+ RPC_U8(&msg, 2) = (uint8_t)restricted;
+ RPC_U8(&msg, 3) = (uint8_t)grant;
+ RPC_U8(&msg, 4) = (uint8_t)coherent;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (pt != NULL) {
+ *pt = RPC_U8(&msg, 0);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_set_confidential(sc_ipc_t ipc, sc_rm_pt_t pt, bool retro)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_SET_CONFIDENTIAL;
+ RPC_U8(&msg, 0) = pt;
+ RPC_U8(&msg, 1) = (uint8_t)retro;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_partition_free(sc_ipc_t ipc, sc_rm_pt_t pt)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_PARTITION_FREE;
+ RPC_U8(&msg, 0) = pt;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_rm_did_t sc_rm_get_did(sc_ipc_t ipc)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_GET_DID;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_rm_did_t) result;
+}
+
+sc_err_t sc_rm_partition_static(sc_ipc_t ipc, sc_rm_pt_t pt, sc_rm_did_t did)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_PARTITION_STATIC;
+ RPC_U8(&msg, 0) = pt;
+ RPC_U8(&msg, 1) = did;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_partition_lock(sc_ipc_t ipc, sc_rm_pt_t pt)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_PARTITION_LOCK;
+ RPC_U8(&msg, 0) = pt;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_get_partition(sc_ipc_t ipc, sc_rm_pt_t *pt)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_GET_PARTITION;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (pt != NULL) {
+ *pt = RPC_U8(&msg, 0);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_set_parent(sc_ipc_t ipc, sc_rm_pt_t pt, sc_rm_pt_t pt_parent)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_SET_PARENT;
+ RPC_U8(&msg, 0) = pt;
+ RPC_U8(&msg, 1) = pt_parent;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_move_all(sc_ipc_t ipc, sc_rm_pt_t pt_src, sc_rm_pt_t pt_dst,
+ bool move_rsrc, bool move_pads)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_MOVE_ALL;
+ RPC_U8(&msg, 0) = pt_src;
+ RPC_U8(&msg, 1) = pt_dst;
+ RPC_U8(&msg, 2) = (uint8_t)move_rsrc;
+ RPC_U8(&msg, 3) = (uint8_t)move_pads;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_assign_resource(sc_ipc_t ipc, sc_rm_pt_t pt, sc_rsrc_t resource)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_ASSIGN_RESOURCE;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = pt;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_set_resource_movable(sc_ipc_t ipc, sc_rsrc_t resource_fst,
+ sc_rsrc_t resource_lst, bool movable)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_SET_RESOURCE_MOVABLE;
+ RPC_U16(&msg, 0) = resource_fst;
+ RPC_U16(&msg, 2) = resource_lst;
+ RPC_U8(&msg, 4) = (uint8_t)movable;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_set_subsys_rsrc_movable(sc_ipc_t ipc, sc_rsrc_t resource,
+ bool movable)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_SET_SUBSYS_RSRC_MOVABLE;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = (uint8_t)movable;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_set_master_attributes(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_rm_spa_t sa, sc_rm_spa_t pa,
+ bool smmu_bypass)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_SET_MASTER_ATTRIBUTES;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = sa;
+ RPC_U8(&msg, 3) = pa;
+ RPC_U8(&msg, 4) = (uint8_t)smmu_bypass;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_set_master_sid(sc_ipc_t ipc, sc_rsrc_t resource, sc_rm_sid_t sid)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_SET_MASTER_SID;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U16(&msg, 2) = sid;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_set_peripheral_permissions(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_rm_pt_t pt, sc_rm_perm_t perm)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_SET_PERIPHERAL_PERMISSIONS;
+ RPC_U16(&msg, 0) = resource;
+ RPC_U8(&msg, 2) = pt;
+ RPC_U8(&msg, 3) = perm;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+bool sc_rm_is_resource_owned(sc_ipc_t ipc, sc_rsrc_t resource)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_IS_RESOURCE_OWNED;
+ RPC_U16(&msg, 0) = resource;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (bool)result;
+}
+
+bool sc_rm_is_resource_master(sc_ipc_t ipc, sc_rsrc_t resource)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_IS_RESOURCE_MASTER;
+ RPC_U16(&msg, 0) = resource;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (bool)result;
+}
+
+bool sc_rm_is_resource_peripheral(sc_ipc_t ipc, sc_rsrc_t resource)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_IS_RESOURCE_PERIPHERAL;
+ RPC_U16(&msg, 0) = resource;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (bool)result;
+}
+
+sc_err_t sc_rm_get_resource_info(sc_ipc_t ipc, sc_rsrc_t resource,
+ sc_rm_sid_t *sid)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_GET_RESOURCE_INFO;
+ RPC_U16(&msg, 0) = resource;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (sid != NULL) {
+ *sid = RPC_U16(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_memreg_alloc(sc_ipc_t ipc, sc_rm_mr_t *mr,
+ sc_faddr_t addr_start, sc_faddr_t addr_end)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_MEMREG_ALLOC;
+ RPC_U32(&msg, 0) = (uint32_t)(addr_start >> 32u);
+ RPC_U32(&msg, 4) = (uint32_t)addr_start;
+ RPC_U32(&msg, 8) = (uint32_t)(addr_end >> 32u);
+ RPC_U32(&msg, 12) = (uint32_t)addr_end;
+ RPC_SIZE(&msg) = 5;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (mr != NULL) {
+ *mr = RPC_U8(&msg, 0);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_memreg_split(sc_ipc_t ipc, sc_rm_mr_t mr,
+ sc_rm_mr_t *mr_ret, sc_faddr_t addr_start,
+ sc_faddr_t addr_end)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_MEMREG_SPLIT;
+ RPC_U32(&msg, 0) = (uint32_t)(addr_start >> 32u);
+ RPC_U32(&msg, 4) = (uint32_t)addr_start;
+ RPC_U32(&msg, 8) = (uint32_t)(addr_end >> 32u);
+ RPC_U32(&msg, 12) = (uint32_t)addr_end;
+ RPC_U8(&msg, 16) = mr;
+ RPC_SIZE(&msg) = 6;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (mr_ret != NULL) {
+ *mr_ret = RPC_U8(&msg, 0);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_memreg_free(sc_ipc_t ipc, sc_rm_mr_t mr)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_MEMREG_FREE;
+ RPC_U8(&msg, 0) = mr;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_find_memreg(sc_ipc_t ipc, sc_rm_mr_t *mr,
+ sc_faddr_t addr_start, sc_faddr_t addr_end)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_FIND_MEMREG;
+ RPC_U32(&msg, 0) = (uint32_t)(addr_start >> 32u);
+ RPC_U32(&msg, 4) = (uint32_t)addr_start;
+ RPC_U32(&msg, 8) = (uint32_t)(addr_end >> 32u);
+ RPC_U32(&msg, 12) = (uint32_t)addr_end;
+ RPC_SIZE(&msg) = 5;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ if (mr != NULL) {
+ *mr = RPC_U8(&msg, 0);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_assign_memreg(sc_ipc_t ipc, sc_rm_pt_t pt, sc_rm_mr_t mr)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_ASSIGN_MEMREG;
+ RPC_U8(&msg, 0) = pt;
+ RPC_U8(&msg, 1) = mr;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_set_memreg_permissions(sc_ipc_t ipc, sc_rm_mr_t mr,
+ sc_rm_pt_t pt, sc_rm_perm_t perm)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_SET_MEMREG_PERMISSIONS;
+ RPC_U8(&msg, 0) = mr;
+ RPC_U8(&msg, 1) = pt;
+ RPC_U8(&msg, 2) = perm;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+bool sc_rm_is_memreg_owned(sc_ipc_t ipc, sc_rm_mr_t mr)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_IS_MEMREG_OWNED;
+ RPC_U8(&msg, 0) = mr;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (bool)result;
+}
+
+sc_err_t sc_rm_get_memreg_info(sc_ipc_t ipc, sc_rm_mr_t mr,
+ sc_faddr_t *addr_start, sc_faddr_t *addr_end)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_GET_MEMREG_INFO;
+ RPC_U8(&msg, 0) = mr;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (addr_start != NULL) {
+ *addr_start =
+ ((uint64_t) RPC_U32(&msg, 0) << 32u) | RPC_U32(&msg, 4);
+ }
+
+ if (addr_end != NULL) {
+ *addr_end =
+ ((uint64_t) RPC_U32(&msg, 8) << 32u) | RPC_U32(&msg, 12);
+ }
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_assign_pad(sc_ipc_t ipc, sc_rm_pt_t pt, sc_pad_t pad)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_ASSIGN_PAD;
+ RPC_U16(&msg, 0) = pad;
+ RPC_U8(&msg, 2) = pt;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_rm_set_pad_movable(sc_ipc_t ipc, sc_pad_t pad_fst,
+ sc_pad_t pad_lst, bool movable)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_SET_PAD_MOVABLE;
+ RPC_U16(&msg, 0) = pad_fst;
+ RPC_U16(&msg, 2) = pad_lst;
+ RPC_U8(&msg, 4) = (uint8_t)movable;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+bool sc_rm_is_pad_owned(sc_ipc_t ipc, sc_pad_t pad)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_IS_PAD_OWNED;
+ RPC_U8(&msg, 0) = pad;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (bool)result;
+}
+
+void sc_rm_dump(sc_ipc_t ipc)
+{
+ sc_rpc_msg_t msg;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_RM;
+ RPC_FUNC(&msg) = (uint8_t)RM_FUNC_DUMP;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ return;
+}
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/timer/rpc.h b/drivers/soc/imx/sc/svc/timer/rpc.h
new file mode 100644
index 000000000000..42413a049ea4
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/timer/rpc.h
@@ -0,0 +1,64 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * Header file for the TIMER RPC implementation.
+ *
+ * @addtogroup TIMER_SVC
+ * @{
+ */
+
+#ifndef _SC_TIMER_RPC_H
+#define _SC_TIMER_RPC_H
+
+/* Includes */
+
+/* Defines */
+
+/* Types */
+
+/*!
+ * This type is used to indicate RPC TIMER function calls.
+ */
+typedef enum timer_func_e {
+ TIMER_FUNC_UNKNOWN = 0, /* Unknown function */
+ TIMER_FUNC_SET_WDOG_TIMEOUT = 1, /* Index for timer_set_wdog_timeout() RPC call */
+ TIMER_FUNC_SET_WDOG_PRE_TIMEOUT = 12, /* Index for timer_set_wdog_pre_timeout() RPC call */
+ TIMER_FUNC_START_WDOG = 2, /* Index for timer_start_wdog() RPC call */
+ TIMER_FUNC_STOP_WDOG = 3, /* Index for timer_stop_wdog() RPC call */
+ TIMER_FUNC_PING_WDOG = 4, /* Index for timer_ping_wdog() RPC call */
+ TIMER_FUNC_GET_WDOG_STATUS = 5, /* Index for timer_get_wdog_status() RPC call */
+ TIMER_FUNC_PT_GET_WDOG_STATUS = 13, /* Index for timer_pt_get_wdog_status() RPC call */
+ TIMER_FUNC_SET_WDOG_ACTION = 10, /* Index for timer_set_wdog_action() RPC call */
+ TIMER_FUNC_SET_RTC_TIME = 6, /* Index for timer_set_rtc_time() RPC call */
+ TIMER_FUNC_GET_RTC_TIME = 7, /* Index for timer_get_rtc_time() RPC call */
+ TIMER_FUNC_GET_RTC_SEC1970 = 9, /* Index for timer_get_rtc_sec1970() RPC call */
+ TIMER_FUNC_SET_RTC_ALARM = 8, /* Index for timer_set_rtc_alarm() RPC call */
+ TIMER_FUNC_SET_RTC_CALB = 11, /* Index for timer_set_rtc_calb() RPC call */
+} timer_func_t;
+
+/* Functions */
+
+/*!
+ * This function dispatches an incoming TIMER RPC request.
+ *
+ * @param[in] caller_pt caller partition
+ * @param[in] msg pointer to RPC message
+ */
+void timer_dispatch(sc_rm_pt_t caller_pt, sc_rpc_msg_t *msg);
+
+/*!
+ * This function translates and dispatches an TIMER RPC request.
+ *
+ * @param[in] ipc IPC handle
+ * @param[in] msg pointer to RPC message
+ */
+void timer_xlate(sc_ipc_t ipc, sc_rpc_msg_t *msg);
+
+#endif /* _SC_TIMER_RPC_H */
+
+/**@}*/
diff --git a/drivers/soc/imx/sc/svc/timer/rpc_clnt.c b/drivers/soc/imx/sc/svc/timer/rpc_clnt.c
new file mode 100644
index 000000000000..badb79e44c41
--- /dev/null
+++ b/drivers/soc/imx/sc/svc/timer/rpc_clnt.c
@@ -0,0 +1,322 @@
+/*
+ * Copyright (C) 2016 Freescale Semiconductor, Inc.
+ * Copyright 2017 NXP
+ *
+ * SPDX-License-Identifier: GPL-2.0+
+ */
+
+/*!
+ * File containing client-side RPC functions for the TIMER service. These
+ * functions are ported to clients that communicate to the SC.
+ *
+ * @addtogroup TIMER_SVC
+ * @{
+ */
+
+/* Includes */
+
+#include <soc/imx8/sc/types.h>
+#include <soc/imx8/sc/svc/rm/api.h>
+#include <soc/imx8/sc/svc/timer/api.h>
+#include "../../main/rpc.h"
+#include "rpc.h"
+
+/* Local Defines */
+
+/* Local Types */
+
+/* Local Functions */
+
+sc_err_t sc_timer_set_wdog_timeout(sc_ipc_t ipc, sc_timer_wdog_time_t timeout)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_SET_WDOG_TIMEOUT;
+ RPC_U32(&msg, 0) = timeout;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_set_wdog_pre_timeout(sc_ipc_t ipc,
+ sc_timer_wdog_time_t pre_timeout)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_SET_WDOG_PRE_TIMEOUT;
+ RPC_U32(&msg, 0) = pre_timeout;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_start_wdog(sc_ipc_t ipc, bool lock)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_START_WDOG;
+ RPC_U8(&msg, 0) = (uint8_t)lock;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_stop_wdog(sc_ipc_t ipc)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_STOP_WDOG;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_ping_wdog(sc_ipc_t ipc)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_PING_WDOG;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_get_wdog_status(sc_ipc_t ipc,
+ sc_timer_wdog_time_t *timeout,
+ sc_timer_wdog_time_t *max_timeout,
+ sc_timer_wdog_time_t *remaining_time)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_GET_WDOG_STATUS;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (timeout != NULL) {
+ *timeout = RPC_U32(&msg, 0);
+ }
+
+ if (max_timeout != NULL) {
+ *max_timeout = RPC_U32(&msg, 4);
+ }
+
+ if (remaining_time != NULL) {
+ *remaining_time = RPC_U32(&msg, 8);
+ }
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_pt_get_wdog_status(sc_ipc_t ipc, sc_rm_pt_t pt, bool *enb,
+ sc_timer_wdog_time_t *timeout,
+ sc_timer_wdog_time_t *remaining_time)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_PT_GET_WDOG_STATUS;
+ RPC_U8(&msg, 0) = pt;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (timeout != NULL) {
+ *timeout = RPC_U32(&msg, 0);
+ }
+
+ if (remaining_time != NULL) {
+ *remaining_time = RPC_U32(&msg, 4);
+ }
+
+ result = RPC_R8(&msg);
+ if (enb != NULL) {
+ *enb = RPC_U8(&msg, 8);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_set_wdog_action(sc_ipc_t ipc,
+ sc_rm_pt_t pt, sc_timer_wdog_action_t action)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_SET_WDOG_ACTION;
+ RPC_U8(&msg, 0) = pt;
+ RPC_U8(&msg, 1) = action;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_set_rtc_time(sc_ipc_t ipc, uint16_t year, uint8_t mon,
+ uint8_t day, uint8_t hour, uint8_t min,
+ uint8_t sec)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_SET_RTC_TIME;
+ RPC_U16(&msg, 0) = year;
+ RPC_U8(&msg, 2) = mon;
+ RPC_U8(&msg, 3) = day;
+ RPC_U8(&msg, 4) = hour;
+ RPC_U8(&msg, 5) = min;
+ RPC_U8(&msg, 6) = sec;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_get_rtc_time(sc_ipc_t ipc, uint16_t *year, uint8_t *mon,
+ uint8_t *day, uint8_t *hour, uint8_t *min,
+ uint8_t *sec)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_GET_RTC_TIME;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (year != NULL) {
+ *year = RPC_U16(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ if (mon != NULL) {
+ *mon = RPC_U8(&msg, 2);
+ }
+
+ if (day != NULL) {
+ *day = RPC_U8(&msg, 3);
+ }
+
+ if (hour != NULL) {
+ *hour = RPC_U8(&msg, 4);
+ }
+
+ if (min != NULL) {
+ *min = RPC_U8(&msg, 5);
+ }
+
+ if (sec != NULL) {
+ *sec = RPC_U8(&msg, 6);
+ }
+
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_get_rtc_sec1970(sc_ipc_t ipc, uint32_t *sec)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_GET_RTC_SEC1970;
+ RPC_SIZE(&msg) = 1;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ if (sec != NULL) {
+ *sec = RPC_U32(&msg, 0);
+ }
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_set_rtc_alarm(sc_ipc_t ipc, uint16_t year, uint8_t mon,
+ uint8_t day, uint8_t hour, uint8_t min,
+ uint8_t sec)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_SET_RTC_ALARM;
+ RPC_U16(&msg, 0) = year;
+ RPC_U8(&msg, 2) = mon;
+ RPC_U8(&msg, 3) = day;
+ RPC_U8(&msg, 4) = hour;
+ RPC_U8(&msg, 5) = min;
+ RPC_U8(&msg, 6) = sec;
+ RPC_SIZE(&msg) = 3;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+sc_err_t sc_timer_set_rtc_calb(sc_ipc_t ipc, int8_t count)
+{
+ sc_rpc_msg_t msg;
+ uint8_t result;
+
+ RPC_VER(&msg) = SC_RPC_VERSION;
+ RPC_SVC(&msg) = (uint8_t)SC_RPC_SVC_TIMER;
+ RPC_FUNC(&msg) = (uint8_t)TIMER_FUNC_SET_RTC_CALB;
+ RPC_I8(&msg, 0) = count;
+ RPC_SIZE(&msg) = 2;
+
+ sc_call_rpc(ipc, &msg, false);
+
+ result = RPC_R8(&msg);
+ return (sc_err_t)result;
+}
+
+/**@}*/