* [PATCH 1/4] drivers: qcom: rpmh-rsc: add RPMH controller for QCOM SoCs
2018-01-19 0:01 [PATCH 0/4] drivers/qcom: add RPMH communication support Lina Iyer
@ 2018-01-19 0:01 ` Lina Iyer
[not found] ` <20180119000157.7380-2-ilina-sgV2jX0FEOL9JmXXK+q4OQ@public.gmane.org>
2018-01-19 0:01 ` [PATCH 2/4] dt-bindings: introduce RPMH RSC bindings for Qualcomm SoCs Lina Iyer
` (2 subsequent siblings)
3 siblings, 1 reply; 18+ messages in thread
From: Lina Iyer @ 2018-01-19 0:01 UTC (permalink / raw)
To: andy.gross, david.brown
Cc: sboyd, rnayak, linux-arm-msm, linux-soc, devicetree, linux-pm,
Lina Iyer
Add controller driver for QCOM SoCs that have hardware based shared
resource management. The hardware IP known as RSC (Resource State
Coordinator) houses multiple Direct Resource Voter (DRV) for different
execution levels. A DRV is a unique voter on the state of a shared
resource. A Trigger Control Set (TCS) is a bunch of slots that can house
multiple resource state requests, that when triggered will issue those
requests through an internal bus to the Resource Power Manager Hardened
(RPMH) blocks. These hardware blocks are capable of adjusting clocks,
voltages etc. The resource state request from a DRV are aggregated along
with state requests from other processors in the SoC and the aggregate
value is applied on the resource.
Some important aspects of the RPMH communication -
- Requests are <addr, value> with some header information
- Multiple requests (upto 16) may be sent through a TCS, at a time
- Requests in a TCS are sent in sequence
- Requests may be fire-n-forget or completion (response expected)
- Multiple TCS from the same DRV may be triggered simultaneously
- Cannot send a request if another reques for the same addr is in
progress from the same DRV
- When all the requests from a TCS are complete, an IRQ is raised
- The IRQ handler needs to clear the TCS before it is available for
reuse
- TCS configuration is specific to a DRV
- Platform drivers may use DRV from different RSCs to make requests
Resource state requests made when CPUs are active are called 'active'
state requests. Requests made when all the CPUs are powered down (idle
state) are called 'sleep' state requests. They are matched by a
corresponding 'wake' state requests which puts the resources back in to
previously requested active state before resuming any CPU. TCSes are
dedicated for each type of requests. Control TCS are used to provide
specific information to the controller.
Only active requests are currently supported by the driver.
Signed-off-by: Lina Iyer <ilina@codeaurora.org>
---
drivers/soc/qcom/Kconfig | 7 +
drivers/soc/qcom/Makefile | 1 +
drivers/soc/qcom/rpmh-internal.h | 24 ++
drivers/soc/qcom/rpmh-rsc.c | 674 ++++++++++++++++++++++++++++++++
include/dt-bindings/soc/qcom,rpmh-rsc.h | 16 +
include/soc/qcom/tcs.h | 38 ++
6 files changed, 760 insertions(+)
create mode 100644 drivers/soc/qcom/rpmh-internal.h
create mode 100644 drivers/soc/qcom/rpmh-rsc.c
create mode 100644 include/dt-bindings/soc/qcom,rpmh-rsc.h
create mode 100644 include/soc/qcom/tcs.h
diff --git a/drivers/soc/qcom/Kconfig b/drivers/soc/qcom/Kconfig
index f21c5d53e721..d331bb9e83d9 100644
--- a/drivers/soc/qcom/Kconfig
+++ b/drivers/soc/qcom/Kconfig
@@ -104,4 +104,11 @@ config QCOM_COMMAND_DB
Command DB queries shared memory by key string for shared system
resources
+config QCOM_RPMH
+ bool "Qualcomm RPM-Hardened (RPMH) Communication"
+ depends on ARCH_QCOM && OF
+ help
+ Support for communication with the hardened-RPM blocks in
+ Qualcomm Technologies Inc (QTI) SoCs.
+
endmenu
diff --git a/drivers/soc/qcom/Makefile b/drivers/soc/qcom/Makefile
index 7b64135b22eb..b7951ce87663 100644
--- a/drivers/soc/qcom/Makefile
+++ b/drivers/soc/qcom/Makefile
@@ -11,3 +11,4 @@ obj-$(CONFIG_QCOM_SMP2P) += smp2p.o
obj-$(CONFIG_QCOM_SMSM) += smsm.o
obj-$(CONFIG_QCOM_WCNSS_CTRL) += wcnss_ctrl.o
obj-$(CONFIG_QCOM_COMMAND_DB) += cmd-db.o
+obj-$(CONFIG_QCOM_RPMH) += rpmh-rsc.o
diff --git a/drivers/soc/qcom/rpmh-internal.h b/drivers/soc/qcom/rpmh-internal.h
new file mode 100644
index 000000000000..0b482f788aa1
--- /dev/null
+++ b/drivers/soc/qcom/rpmh-internal.h
@@ -0,0 +1,24 @@
+/* Copyright (c) 2016-2018, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ */
+
+
+#ifndef __RPM_INTERNAL_H__
+#define __RPM_INTERNAL_H__
+
+#include <soc/qcom/tcs.h>
+
+struct rsc_drv;
+
+int rpmh_rsc_send_data(struct rsc_drv *drv, struct tcs_mbox_msg *msg);
+
+#endif /* __RPM_INTERNAL_H__ */
diff --git a/drivers/soc/qcom/rpmh-rsc.c b/drivers/soc/qcom/rpmh-rsc.c
new file mode 100644
index 000000000000..3e68cef5513e
--- /dev/null
+++ b/drivers/soc/qcom/rpmh-rsc.c
@@ -0,0 +1,674 @@
+/* Copyright (c) 2016-2018, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ */
+
+#define pr_fmt(fmt) "%s " fmt, KBUILD_MODNAME
+
+#include <linux/atomic.h>
+#include <linux/delay.h>
+#include <linux/interrupt.h>
+#include <linux/kernel.h>
+#include <linux/list.h>
+#include <linux/module.h>
+#include <linux/of.h>
+#include <linux/of_address.h>
+#include <linux/of_irq.h>
+#include <linux/of_platform.h>
+#include <linux/platform_device.h>
+#include <linux/slab.h>
+#include <linux/spinlock.h>
+
+#include <asm-generic/io.h>
+#include <soc/qcom/tcs.h>
+#include <dt-bindings/soc/qcom,rpmh-rsc.h>
+
+#include "rpmh-internal.h"
+
+#define MAX_CMDS_PER_TCS 16
+#define MAX_TCS_PER_TYPE 3
+
+#define RSC_DRV_TCS_OFFSET 672
+#define RSC_DRV_CMD_OFFSET 20
+
+/* DRV Configuration Information Register */
+#define DRV_PRNT_CHLD_CONFIG 0x0C
+#define DRV_NUM_TCS_MASK 0x3F
+#define DRV_NUM_TCS_SHIFT 6
+#define DRV_NCPT_MASK 0x1F
+#define DRV_NCPT_SHIFT 27
+
+/* Register offsets */
+#define RSC_DRV_IRQ_ENABLE 0x00
+#define RSC_DRV_IRQ_STATUS 0x04
+#define RSC_DRV_IRQ_CLEAR 0x08
+#define RSC_DRV_CMD_WAIT_FOR_CMPL 0x10
+#define RSC_DRV_CONTROL 0x14
+#define RSC_DRV_STATUS 0x18
+#define RSC_DRV_CMD_ENABLE 0x1C
+#define RSC_DRV_CMD_MSGID 0x30
+#define RSC_DRV_CMD_ADDR 0x34
+#define RSC_DRV_CMD_DATA 0x38
+#define RSC_DRV_CMD_STATUS 0x3C
+#define RSC_DRV_CMD_RESP_DATA 0x40
+
+#define TCS_AMC_MODE_ENABLE BIT(16)
+#define TCS_AMC_MODE_TRIGGER BIT(24)
+
+/* TCS CMD register bit mask */
+#define CMD_MSGID_LEN 8
+#define CMD_MSGID_RESP_REQ BIT(8)
+#define CMD_MSGID_WRITE BIT(16)
+#define CMD_STATUS_ISSUED BIT(8)
+#define CMD_STATUS_COMPL BIT(16)
+
+#define TCS_TYPE_NR 4
+#define MAX_TCS_NR (MAX_TCS_PER_TYPE * TCS_TYPE_NR)
+
+struct rsc_drv;
+
+/**
+ * tcs_response: Response object for a request
+ *
+ * @drv: the controller
+ * @msg: the request for this response
+ * @m: the tcs identifier
+ * @err: error reported in the response
+ * @list: link list object.
+ */
+struct tcs_response {
+ struct rsc_drv *drv;
+ struct tcs_mbox_msg *msg;
+ u32 m;
+ int err;
+ struct list_head list;
+};
+
+/**
+ * tcs_mbox: group of TCSes for a request state
+ *
+ * @type: type of the TCS in this group - active, sleep, wake
+ * @tcs_mask: mask of the TCSes relative to all the TCSes in the RSC
+ * @tcs_offset: start of the TCS group relative to the TCSes in the RSC
+ * @num_tcs: number of TCSes in this type
+ * @ncpt: number of commands in each TCS
+ * @tcs_lock: lock for synchronizing this TCS writes
+ * @responses: response objects for requests sent from each TCS
+ */
+struct tcs_mbox {
+ struct rsc_drv *drv;
+ int type;
+ u32 tcs_mask;
+ u32 tcs_offset;
+ int num_tcs;
+ int ncpt;
+ spinlock_t tcs_lock;
+ struct tcs_response *responses[MAX_TCS_PER_TYPE];
+};
+
+/**
+ * rsc_drv: the RSC controller
+ *
+ * @pdev: platform device of this controller
+ * @name: controller identifier
+ * @base: start address of the controller
+ * @reg_base: start address of the registers in this controller
+ * @drv_id: instance id in the controller (DRV)
+ * @num_tcs: number of TCSes in this DRV
+ * @tasklet: handle responses, off-load work from IRQ handler
+ * @response_pending: list of responses that needs to be sent to caller
+ * @tcs: TCS groups
+ * @tcs_in_use: s/w state of the TCS
+ * @drv_lock: synchronize state of the controller
+ */
+struct rsc_drv {
+ struct platform_device *pdev;
+ const char *name;
+ void __iomem *base;
+ void __iomem *reg_base;
+ int drv_id;
+ int num_tcs;
+ struct tasklet_struct tasklet;
+ struct list_head response_pending;
+ struct tcs_mbox tcs[TCS_TYPE_NR];
+ atomic_t tcs_in_use[MAX_TCS_NR];
+ spinlock_t drv_lock;
+};
+
+static inline struct tcs_mbox *get_tcs_from_index(struct rsc_drv *drv, int m)
+{
+ struct tcs_mbox *tcs = NULL;
+ int i;
+
+ for (i = 0; i < drv->num_tcs; i++) {
+ tcs = &drv->tcs[i];
+ if (tcs->tcs_mask & (u32)BIT(m))
+ break;
+ }
+
+ if (i == drv->num_tcs) {
+ WARN(1, "Incorrect TCS index %d", m);
+ tcs = NULL;
+ }
+
+ return tcs;
+}
+
+static struct tcs_response *setup_response(struct rsc_drv *drv,
+ struct tcs_mbox_msg *msg, int m)
+{
+ struct tcs_response *resp;
+ struct tcs_mbox *tcs;
+
+ resp = kcalloc(1, sizeof(*resp), GFP_ATOMIC);
+ if (!resp)
+ return ERR_PTR(-ENOMEM);
+
+ resp->drv = drv;
+ resp->msg = msg;
+ resp->err = 0;
+
+ tcs = get_tcs_from_index(drv, m);
+ if (!tcs)
+ return ERR_PTR(-EINVAL);
+
+ /*
+ * We should have been called from a TCS-type locked context, and
+ * we overwrite the previously saved response.
+ */
+ tcs->responses[m - tcs->tcs_offset] = resp;
+
+ return resp;
+}
+
+static void free_response(struct tcs_response *resp)
+{
+ kfree(resp);
+}
+
+static inline struct tcs_response *get_response(struct rsc_drv *drv, u32 m)
+{
+ struct tcs_mbox *tcs = get_tcs_from_index(drv, m);
+
+ return tcs->responses[m - tcs->tcs_offset];
+}
+
+static inline u32 read_drv_config(void __iomem *base)
+{
+ return le32_to_cpu(readl_relaxed(base + DRV_PRNT_CHLD_CONFIG));
+}
+
+static inline u32 read_tcs_reg(void __iomem *base, int reg, int m, int n)
+{
+ return le32_to_cpu(readl_relaxed(base + reg +
+ RSC_DRV_TCS_OFFSET * m + RSC_DRV_CMD_OFFSET * n));
+}
+
+static inline void write_tcs_reg(void __iomem *base, int reg, int m, int n,
+ u32 data)
+{
+ writel_relaxed(cpu_to_le32(data), base + reg +
+ RSC_DRV_TCS_OFFSET * m + RSC_DRV_CMD_OFFSET * n);
+}
+
+static inline void write_tcs_reg_sync(void __iomem *base, int reg, int m, int n,
+ u32 data)
+{
+ do {
+ write_tcs_reg(base, reg, m, n, data);
+ if (data == read_tcs_reg(base, reg, m, n))
+ break;
+ udelay(1);
+ } while (1);
+}
+
+static inline bool tcs_is_free(struct rsc_drv *drv, int m)
+{
+ void __iomem *base = drv->reg_base;
+
+ return read_tcs_reg(base, RSC_DRV_STATUS, m, 0) &&
+ !atomic_read(&drv->tcs_in_use[m]);
+}
+
+static inline struct tcs_mbox *get_tcs_of_type(struct rsc_drv *drv, int type)
+{
+ int i;
+ struct tcs_mbox *tcs;
+
+ for (i = 0; i < TCS_TYPE_NR; i++)
+ if (type == drv->tcs[i].type)
+ break;
+
+ if (i == TCS_TYPE_NR)
+ return ERR_PTR(-EINVAL);
+
+ tcs = &drv->tcs[i];
+ if (!tcs->num_tcs)
+ return ERR_PTR(-EINVAL);
+
+ return tcs;
+}
+
+static inline struct tcs_mbox *get_tcs_for_msg(struct rsc_drv *drv,
+ struct tcs_mbox_msg *msg)
+{
+ int type = -1;
+
+ switch (msg->state) {
+ case RPMH_ACTIVE_ONLY_STATE:
+ type = ACTIVE_TCS;
+ break;
+ default:
+ break;
+ }
+
+ if (type < 0)
+ return ERR_PTR(-EINVAL);
+
+ return get_tcs_of_type(drv, type);
+}
+
+static inline void send_tcs_response(struct tcs_response *resp)
+{
+ struct rsc_drv *drv = resp->drv;
+ unsigned long flags;
+
+ spin_lock_irqsave(&drv->drv_lock, flags);
+ INIT_LIST_HEAD(&resp->list);
+ list_add_tail(&resp->list, &drv->response_pending);
+ spin_unlock_irqrestore(&drv->drv_lock, flags);
+
+ tasklet_schedule(&drv->tasklet);
+}
+
+/**
+ * tcs_irq_handler: TX Done interrupt handler
+ */
+static irqreturn_t tcs_irq_handler(int irq, void *p)
+{
+ struct rsc_drv *drv = p;
+ void __iomem *base = drv->reg_base;
+ int m, i;
+ u32 irq_status, sts;
+ struct tcs_response *resp;
+ struct tcs_cmd *cmd;
+ int err;
+
+ irq_status = read_tcs_reg(base, RSC_DRV_IRQ_STATUS, 0, 0);
+
+ for (m = 0; m < drv->num_tcs; m++) {
+ if (!(irq_status & (u32)BIT(m)))
+ continue;
+
+ err = 0;
+ resp = get_response(drv, m);
+ if (!resp) {
+ for (i = 0; i < resp->msg->num_payload; i++) {
+ cmd = &resp->msg->payload[i];
+ sts = read_tcs_reg(base, RSC_DRV_CMD_STATUS,
+ m, i);
+ if ((!(sts & CMD_STATUS_ISSUED)) ||
+ ((resp->msg->is_complete ||
+ cmd->complete) &&
+ (!(sts & CMD_STATUS_COMPL)))) {
+ resp->err = -EIO;
+ break;
+ }
+ }
+ }
+
+ write_tcs_reg(base, RSC_DRV_CMD_ENABLE, m, 0, 0);
+ write_tcs_reg(base, RSC_DRV_IRQ_CLEAR, 0, 0, BIT(m));
+ atomic_set(&drv->tcs_in_use[m], 0);
+
+ if (resp) {
+ resp->err = err;
+ send_tcs_response(resp);
+ }
+ }
+
+ return IRQ_HANDLED;
+}
+
+/**
+ * tcs_notify_tx_done: TX Done for requests that got a response
+ *
+ * @data: the tasklet argument
+ *
+ * Tasklet function to notify MBOX that we are done with the request.
+ * Handles all pending reponses whenever run.
+ */
+static void tcs_notify_tx_done(unsigned long data)
+{
+ struct rsc_drv *drv = (struct rsc_drv *)data;
+ struct tcs_response *resp;
+ unsigned long flags;
+ int err;
+
+ do {
+ spin_lock_irqsave(&drv->drv_lock, flags);
+ if (list_empty(&drv->response_pending)) {
+ spin_unlock_irqrestore(&drv->drv_lock, flags);
+ break;
+ }
+ resp = list_first_entry(&drv->response_pending,
+ struct tcs_response, list);
+ list_del(&resp->list);
+ spin_unlock_irqrestore(&drv->drv_lock, flags);
+ err = resp->err;
+ free_response(resp);
+ } while (1);
+}
+
+static void __tcs_buffer_write(struct rsc_drv *drv, int m, int n,
+ struct tcs_mbox_msg *msg)
+{
+ void __iomem *base = drv->reg_base;
+ u32 msgid, cmd_msgid = 0;
+ u32 cmd_enable = 0;
+ u32 cmd_complete;
+ struct tcs_cmd *cmd;
+ int i;
+
+ cmd_msgid = CMD_MSGID_LEN;
+ cmd_msgid |= (msg->is_complete) ? CMD_MSGID_RESP_REQ : 0;
+ cmd_msgid |= CMD_MSGID_WRITE;
+
+ cmd_complete = read_tcs_reg(base, RSC_DRV_CMD_WAIT_FOR_CMPL, m, 0);
+
+ for (i = 0; i < msg->num_payload; i++) {
+ cmd = &msg->payload[i];
+ cmd_enable |= BIT(n + i);
+ cmd_complete |= cmd->complete << (n + i);
+ msgid = cmd_msgid;
+ msgid |= (cmd->complete) ? CMD_MSGID_RESP_REQ : 0;
+ write_tcs_reg(base, RSC_DRV_CMD_MSGID, m, n + i, msgid);
+ write_tcs_reg(base, RSC_DRV_CMD_ADDR, m, n + i, cmd->addr);
+ write_tcs_reg(base, RSC_DRV_CMD_DATA, m, n + i, cmd->data);
+ }
+
+ write_tcs_reg(base, RSC_DRV_CMD_WAIT_FOR_CMPL, m, 0, cmd_complete);
+ cmd_enable |= read_tcs_reg(base, RSC_DRV_CMD_ENABLE, m, 0);
+ write_tcs_reg(base, RSC_DRV_CMD_ENABLE, m, 0, cmd_enable);
+}
+
+static void __tcs_trigger(struct rsc_drv *drv, int m)
+{
+ void __iomem *base = drv->reg_base;
+ u32 enable;
+
+ /*
+ * HW req: Clear the DRV_CONTROL and enable TCS again
+ * While clearing ensure that the AMC mode trigger is cleared
+ * and then the mode enable is cleared.
+ */
+ enable = read_tcs_reg(base, RSC_DRV_CONTROL, m, 0);
+ enable &= ~TCS_AMC_MODE_TRIGGER;
+ write_tcs_reg_sync(base, RSC_DRV_CONTROL, m, 0, enable);
+ enable &= ~TCS_AMC_MODE_ENABLE;
+ write_tcs_reg_sync(base, RSC_DRV_CONTROL, m, 0, enable);
+
+ /* Enable the AMC mode on the TCS and then trigger the TCS */
+ enable = TCS_AMC_MODE_ENABLE;
+ write_tcs_reg_sync(base, RSC_DRV_CONTROL, m, 0, enable);
+ enable |= TCS_AMC_MODE_TRIGGER;
+ write_tcs_reg_sync(base, RSC_DRV_CONTROL, m, 0, enable);
+}
+
+static int check_for_req_inflight(struct rsc_drv *drv, struct tcs_mbox *tcs,
+ struct tcs_mbox_msg *msg)
+{
+ u32 curr_enabled, addr;
+ int i, j, k;
+ void __iomem *base = drv->reg_base;
+ int m = tcs->tcs_offset;
+
+ for (i = 0; i < tcs->num_tcs; i++, m++) {
+ if (tcs_is_free(drv, m))
+ continue;
+
+ curr_enabled = read_tcs_reg(base, RSC_DRV_CMD_ENABLE, m, 0);
+
+ for (j = 0; j < MAX_CMDS_PER_TCS; j++) {
+ if (!(curr_enabled & (u32)BIT(j)))
+ continue;
+
+ addr = read_tcs_reg(base, RSC_DRV_CMD_ADDR, m, j);
+ for (k = 0; k < msg->num_payload; k++) {
+ if (addr == msg->payload[k].addr)
+ return -EBUSY;
+ }
+ }
+ }
+
+ return 0;
+}
+
+static int find_free_tcs(struct tcs_mbox *tcs)
+{
+ int m;
+
+ for (m = 0; m < tcs->num_tcs; m++)
+ if (tcs_is_free(tcs->drv, tcs->tcs_offset + m))
+ break;
+
+ return (m != tcs->num_tcs) ? m : -EBUSY;
+}
+
+static int tcs_mbox_write(struct rsc_drv *drv, struct tcs_mbox_msg *msg)
+{
+ struct tcs_mbox *tcs;
+ int m;
+ struct tcs_response *resp = NULL;
+ unsigned long flags;
+ int ret = 0;
+
+ tcs = get_tcs_for_msg(drv, msg);
+ if (IS_ERR(tcs))
+ return PTR_ERR(tcs);
+
+ spin_lock_irqsave(&tcs->tcs_lock, flags);
+ m = find_free_tcs(tcs);
+ if (m < 0) {
+ ret = m;
+ goto done_write;
+ }
+
+ /*
+ * The h/w does not like if we send a request to the same address,
+ * when one is already in-flight or bring processed.
+ */
+ ret = check_for_req_inflight(drv, tcs, msg);
+ if (ret)
+ goto done_write;
+
+ resp = setup_response(drv, msg, m);
+ if (IS_ERR_OR_NULL(resp)) {
+ ret = PTR_ERR(resp);
+ goto done_write;
+ }
+ resp->m = m;
+
+ atomic_set(&drv->tcs_in_use[m], 1);
+ __tcs_buffer_write(drv, m, 0, msg);
+ __tcs_trigger(drv, m);
+
+done_write:
+ spin_unlock_irqrestore(&tcs->tcs_lock, flags);
+ return ret;
+}
+
+/**
+ * rpmh_rsc_send_data: Validate the incoming message and write to the
+ * appropriate TCS block.
+ *
+ * @drv: the controller
+ * @msg: the data to be sent
+ *
+ * Returns a negative error for invalid message structure and invalid
+ * message combination, -EBUSY if there is an other active request for
+ * the channel in process, otherwise bubbles up internal error.
+ */
+int rpmh_rsc_send_data(struct rsc_drv *drv, struct tcs_mbox_msg *msg)
+{
+ int ret = 0;
+
+ if (!msg || !msg->payload || !msg->num_payload ||
+ msg->num_payload > MAX_RPMH_PAYLOAD)
+ return -EINVAL;
+
+ do {
+ ret = tcs_mbox_write(drv, msg);
+ if (ret == -EBUSY) {
+ pr_info_ratelimited(
+ "TCS Busy, retrying RPMH message send: addr=0x%x\n",
+ msg->payload[0].addr);
+ udelay(10);
+ }
+ } while (ret == -EBUSY);
+
+ return ret;
+}
+EXPORT_SYMBOL(rpmh_rsc_send_data);
+
+static int rpmh_rsc_probe(struct platform_device *pdev)
+{
+ struct device_node *dn = pdev->dev.of_node;
+ struct rsc_drv *drv;
+ struct tcs_mbox *tcs;
+ int irq;
+ u32 val[8] = { 0 };
+ int st = 0;
+ int i, ret, nelem;
+ u32 config, max_tcs, ncpt;
+ int tcs_type_count[TCS_TYPE_NR] = { 0 };
+ struct resource *res;
+
+ drv = devm_kzalloc(&pdev->dev, sizeof(*drv), GFP_KERNEL);
+ if (!drv)
+ return -ENOMEM;
+
+ ret = of_property_read_u32(dn, "qcom,drv-id", &drv->drv_id);
+ if (ret)
+ return ret;
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (!res)
+ return -EINVAL;
+ drv->base = devm_ioremap_resource(&pdev->dev, res);
+ if (IS_ERR(drv->base))
+ return PTR_ERR(drv->base);
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 1);
+ if (!res)
+ return -EINVAL;
+ drv->reg_base = devm_ioremap_resource(&pdev->dev, res);
+ if (IS_ERR(drv->reg_base))
+ return PTR_ERR(drv->reg_base);
+
+ config = read_drv_config(drv->base);
+ max_tcs = config & (DRV_NUM_TCS_MASK <<
+ (DRV_NUM_TCS_SHIFT * drv->drv_id));
+ max_tcs = max_tcs >> (DRV_NUM_TCS_SHIFT * drv->drv_id);
+ ncpt = config & (DRV_NCPT_MASK << DRV_NCPT_SHIFT);
+ ncpt = ncpt >> DRV_NCPT_SHIFT;
+
+ nelem = of_property_count_elems_of_size(dn, "qcom,tcs-config",
+ sizeof(u32));
+ if (!nelem || (nelem % 2) || (nelem > 2 * TCS_TYPE_NR))
+ return -EINVAL;
+
+ ret = of_property_read_u32_array(dn, "qcom,tcs-config", val, nelem);
+ if (ret)
+ return ret;
+
+ for (i = 0; i < (nelem / 2); i++) {
+ if (val[2 * i] >= TCS_TYPE_NR)
+ return -EINVAL;
+ tcs_type_count[val[2 * i]]++;
+ if (tcs_type_count[val[2 * i]] > 1)
+ return -EINVAL;
+ }
+
+ for (i = 0; i < ARRAY_SIZE(tcs_type_count); i++)
+ if (!tcs_type_count[i])
+ return -EINVAL;
+
+ for (i = 0; i < (nelem / 2); i++) {
+ tcs = &drv->tcs[val[2 * i]];
+ tcs->drv = drv;
+ tcs->type = val[2 * i];
+ tcs->num_tcs = val[2 * i + 1];
+ tcs->ncpt = ncpt;
+ spin_lock_init(&tcs->tcs_lock);
+
+ if (tcs->num_tcs <= 0 || tcs->type == CONTROL_TCS)
+ continue;
+
+ if (tcs->num_tcs > MAX_TCS_PER_TYPE ||
+ st + tcs->num_tcs > max_tcs ||
+ st + tcs->num_tcs >= 8 * sizeof(tcs->tcs_mask))
+ return -EINVAL;
+
+ tcs->tcs_mask = ((1 << tcs->num_tcs) - 1) << st;
+ tcs->tcs_offset = st;
+ st += tcs->num_tcs;
+ }
+
+ drv->num_tcs = st;
+ drv->pdev = pdev;
+ INIT_LIST_HEAD(&drv->response_pending);
+ spin_lock_init(&drv->drv_lock);
+ tasklet_init(&drv->tasklet, tcs_notify_tx_done, (unsigned long)drv);
+
+ drv->name = of_get_property(pdev->dev.of_node, "label", NULL);
+ if (!drv->name)
+ drv->name = dev_name(&pdev->dev);
+
+ irq = of_irq_get(dn, 0);
+ if (irq < 0)
+ return irq;
+
+ ret = devm_request_irq(&pdev->dev, irq, tcs_irq_handler,
+ IRQF_TRIGGER_HIGH | IRQF_NO_SUSPEND, drv->name, drv);
+ if (ret)
+ return ret;
+
+ write_tcs_reg(drv->reg_base, RSC_DRV_IRQ_ENABLE, 0, 0,
+ drv->tcs[ACTIVE_TCS].tcs_mask);
+
+ for (i = 0; i < ARRAY_SIZE(drv->tcs_in_use); i++)
+ atomic_set(&drv->tcs_in_use[i], 0);
+
+ dev_set_drvdata(&pdev->dev, drv);
+
+ return of_platform_populate(pdev->dev.of_node, NULL, NULL, &pdev->dev);
+}
+
+static const struct of_device_id rpmh_drv_match[] = {
+ { .compatible = "qcom,rpmh-rsc", },
+ { }
+};
+MODULE_DEVICE_TABLE(of, rpm_drv_match);
+
+static struct platform_driver rpmh_driver = {
+ .probe = rpmh_rsc_probe,
+ .driver = {
+ .name = KBUILD_MODNAME,
+ .of_match_table = rpmh_drv_match,
+ },
+};
+
+static int __init rpmh_driver_init(void)
+{
+ return platform_driver_register(&rpmh_driver);
+}
+arch_initcall(rpmh_driver_init);
diff --git a/include/dt-bindings/soc/qcom,rpmh-rsc.h b/include/dt-bindings/soc/qcom,rpmh-rsc.h
new file mode 100644
index 000000000000..24a56a5cf096
--- /dev/null
+++ b/include/dt-bindings/soc/qcom,rpmh-rsc.h
@@ -0,0 +1,16 @@
+/* Copyright (c) 2016-2018, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#define SLEEP_TCS 0
+#define WAKE_TCS 1
+#define ACTIVE_TCS 2
+#define CONTROL_TCS 3
diff --git a/include/soc/qcom/tcs.h b/include/soc/qcom/tcs.h
new file mode 100644
index 000000000000..07cf6d8d43e3
--- /dev/null
+++ b/include/soc/qcom/tcs.h
@@ -0,0 +1,38 @@
+/* Copyright (c) 2016-2018, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ */
+
+#ifndef __SOC_QCOM_TCS_H__
+#define __SOC_QCOM_TCS_H__
+
+#define MAX_RPMH_PAYLOAD 16
+
+struct tcs_cmd {
+ u32 addr; /* slv_id:18:16 | offset:0:15 */
+ u32 data; /* data for resource (or read response) */
+ bool complete; /* wait for completion before sending next */
+};
+
+enum rpmh_state {
+ RPMH_ACTIVE_ONLY_STATE, /* Active only (= AMC) */
+ RPMH_WAKE_ONLY_STATE, /* Wake only */
+ RPMH_SLEEP_STATE, /* Sleep */
+};
+
+struct tcs_mbox_msg {
+ enum rpmh_state state; /* request state */
+ bool is_complete; /* wait for resp from accelerator */
+ u32 num_payload; /* Limited to MAX_RPMH_PAYLOAD in one msg */
+ struct tcs_cmd *payload;/* array of tcs_cmds */
+};
+
+#endif /* __SOC_QCOM_TCS_H__ */
--
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum,
a Linux Foundation Collaborative Project
^ permalink raw reply related [flat|nested] 18+ messages in thread
* [PATCH 2/4] dt-bindings: introduce RPMH RSC bindings for Qualcomm SoCs
2018-01-19 0:01 [PATCH 0/4] drivers/qcom: add RPMH communication support Lina Iyer
2018-01-19 0:01 ` [PATCH 1/4] drivers: qcom: rpmh-rsc: add RPMH controller for QCOM SoCs Lina Iyer
@ 2018-01-19 0:01 ` Lina Iyer
2018-01-29 19:33 ` Rob Herring
2018-02-03 19:11 ` Bjorn Andersson
2018-01-19 0:01 ` [PATCH 3/4] drivers: qcom: rpmh-rsc: log RPMH requests in FTRACE Lina Iyer
2018-01-19 0:01 ` [PATCH 4/4] drivers: qcom: rpmh: add RPMH helper functions Lina Iyer
3 siblings, 2 replies; 18+ messages in thread
From: Lina Iyer @ 2018-01-19 0:01 UTC (permalink / raw)
To: andy.gross, david.brown
Cc: sboyd, rnayak, linux-arm-msm, linux-soc, devicetree, linux-pm,
Lina Iyer
Add device binding documentation for Qualcomm Technology Inc's RPMH RSC
driver. The hardware block is used for communicating resource state
requests for shared resources.
Cc: devicetree@vger.kernel.org
Signed-off-by: Lina Iyer <ilina@codeaurora.org>
---
.../devicetree/bindings/arm/msm/rpmh-rsc.txt | 134 +++++++++++++++++++++
1 file changed, 134 insertions(+)
create mode 100644 Documentation/devicetree/bindings/arm/msm/rpmh-rsc.txt
diff --git a/Documentation/devicetree/bindings/arm/msm/rpmh-rsc.txt b/Documentation/devicetree/bindings/arm/msm/rpmh-rsc.txt
new file mode 100644
index 000000000000..b0cd55caf916
--- /dev/null
+++ b/Documentation/devicetree/bindings/arm/msm/rpmh-rsc.txt
@@ -0,0 +1,134 @@
+RPMH RSC:
+------------
+
+RPMH is the mechanism for communicating with the hardened resource
+accelerators. Requests to the resources can be written to the TCS mailbox
+registers and using a (addr, val) pair and triggered. Messages in the TCS are
+then sent in sequence over an internal bus.
+
+The hardware block (Direct Resource Voter or DRV) is a part of the h/w entity
+(Resource State Coordinator a.k.a RSC) that can handle a multiple sleep and
+active/wake resource requests. Multiple such DRVs can exist in a SoC and can
+be written to from Linux. The structure of each DRV follows the same template
+with a few variations that are captured by the properties here.
+
+Each DRV could have 'm' TCS instances. Each TCS could have 'n' slots. Each
+slot has a header (u32), address (u32), data (u32), status (u32) and a
+read-response (u32). A TCS when triggered will send all the enabled commands
+of the 'n' commands in that slot in sequence.
+
+A TCS may be triggered from Linux or triggered by the F/W after all the CPUs
+have powered off to faciliate idle power saving. TCS could be classified as -
+
+ SLEEP, /* Triggered by F/W */
+ WAKE, /* Triggered by F/W */
+ ACTIVE, /* Triggered by Linux */
+ CONTROL /* Triggered by F/W */
+
+The order in which they are described in the DT, should match the hardware
+configuration.
+
+Requests can be made for the state of a resource, when the subsystem is active
+or idle. When all subsystems like Modem, GPU, CPU are idle, the resource state
+will be an aggregeate of the sleep votes from each of those subsystem. Drivers
+may request a sleep value for their shared resources in addition to the active
+mode requests.
+
+Control requests are instance specific requests that may or may not reach an
+accelerator. Only one platform device in Linux can request a control channel
+on a DRV.
+
+CONTROLLER:
+----------
+
+PROPERTIES:
+
+- compatible:
+ Usage: required
+ Value type: <string>
+ Definition: Should be "qcom,rpmh-rsc".
+
+- reg:
+ Usage: required
+ Value type: <prop-encoded-array>
+ Definition: the first element specifies the base address of the DRV,
+ the second element specifies the size of the region.
+
+- interrupts:
+ Usage: required
+ Value type: <prop-encoded-interrupt>
+ Definition: the interrupt that trips when a message complete/response
+ is received for this DRV from the accelertors.
+
+- qcom,drv-id:
+ Usage: required
+ Value type: <u32>
+ Definition: the id of the DRV in the RSC block.
+
+- qcom, tcs-config:
+ Usage: required
+ Value type: <prop-encoded-array>
+ Definition: the tuple definining the configuration of TCS.
+ Must have 2 cells which describe each TCS type.
+ <type number_of_tcs>
+ - Cell #1 (TCS Type): TCS types can be specified -
+ SLEEP_TCS
+ WAKE_TCS
+ ACTIVE_TCS
+ CONTROL_TCS
+ - Cell #2 (Number of TCS): <u32>
+
+- label:
+ Usage: optional
+ Value type: <string>
+ Definition: Name for the RSC. The name would be used in trace logs.
+
+Clients the want to use the RSC to communicate with RPMH would specify their
+bindings as child of the corresponding RSC controllers.
+
+EXAMPLE 1:
+
+For a TCS whose RSC base address is is 0x179C0000 and is at a DRV of 2, the
+register offsets for DRV2 start at 0D00, the register calculations are like
+this -
+First tuple: 0x179C0000 + 0x10000 * 2 = 0x179E0000
+Second tuple: 0x179E0000 + 0xD00 = 0x179E0D00
+
+ apps_rsc: rsc@179e000 {
+ compatible = "qcom,rpmh-rsc";
+ label = "apps_rsc";
+ reg = <0x179e0000 0x10000>, <0x179e0d00 0x3000>;
+ interrupts = <0 5 0>;
+ qcom,drv-id = <2>;
+ qcom,tcs-config = <SLEEP_TCS 3>,
+ <WAKE_TCS 3>,
+ <ACTIVE_TCS 2>,
+ <CONTROL_TCS 1>;
+
+ foo-clk {
+ compatible = "foo-clk";
+ };
+ };
+
+EXAMPLE 2:
+
+For a TCS whose RSC base address is 0xAF20000 and is at DRV of 0, the register
+offsets for DRV0 start at 01C00, the register calculations are like this -
+First tuple: 0xAF20000
+Second tuple: 0xAF20000 + 0x1C00
+
+ disp_rsc: rsc@af20000 {
+ label = "disp_rsc";
+ compatible = "qcom,rpmh-rsc";
+ reg = <0xaf20000 0x10000>, <0xaf21c00 0x3000>;
+ interrupts = <0 129 0>;
+ qcom,drv-id = <0>;
+ qcom,tcs-config = <SLEEP_TCS 1>,
+ <WAKE_TCS 1>,
+ <ACTIVE_TCS 0>,
+ <CONTROL_TCS 1>;
+
+ foo-clk {
+ compatible = "foo-clk";
+ };
+ };
--
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum,
a Linux Foundation Collaborative Project
^ permalink raw reply related [flat|nested] 18+ messages in thread
* Re: [PATCH 2/4] dt-bindings: introduce RPMH RSC bindings for Qualcomm SoCs
2018-01-19 0:01 ` [PATCH 2/4] dt-bindings: introduce RPMH RSC bindings for Qualcomm SoCs Lina Iyer
@ 2018-01-29 19:33 ` Rob Herring
2018-01-30 16:24 ` Lina Iyer
2018-02-03 19:11 ` Bjorn Andersson
1 sibling, 1 reply; 18+ messages in thread
From: Rob Herring @ 2018-01-29 19:33 UTC (permalink / raw)
To: Lina Iyer
Cc: andy.gross, david.brown, sboyd, rnayak, linux-arm-msm, linux-soc,
devicetree, linux-pm
On Thu, Jan 18, 2018 at 05:01:55PM -0700, Lina Iyer wrote:
> Add device binding documentation for Qualcomm Technology Inc's RPMH RSC
> driver. The hardware block is used for communicating resource state
> requests for shared resources.
>
> Cc: devicetree@vger.kernel.org
> Signed-off-by: Lina Iyer <ilina@codeaurora.org>
> ---
> .../devicetree/bindings/arm/msm/rpmh-rsc.txt | 134 +++++++++++++++++++++
bindings/mailbox instead?
> 1 file changed, 134 insertions(+)
> create mode 100644 Documentation/devicetree/bindings/arm/msm/rpmh-rsc.txt
>
> diff --git a/Documentation/devicetree/bindings/arm/msm/rpmh-rsc.txt b/Documentation/devicetree/bindings/arm/msm/rpmh-rsc.txt
> new file mode 100644
> index 000000000000..b0cd55caf916
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/arm/msm/rpmh-rsc.txt
> @@ -0,0 +1,134 @@
> +RPMH RSC:
> +------------
> +
> +RPMH is the mechanism for communicating with the hardened resource
> +accelerators. Requests to the resources can be written to the TCS mailbox
> +registers and using a (addr, val) pair and triggered. Messages in the TCS are
> +then sent in sequence over an internal bus.
> +
> +The hardware block (Direct Resource Voter or DRV) is a part of the h/w entity
> +(Resource State Coordinator a.k.a RSC) that can handle a multiple sleep and
> +active/wake resource requests. Multiple such DRVs can exist in a SoC and can
> +be written to from Linux. The structure of each DRV follows the same template
> +with a few variations that are captured by the properties here.
> +
> +Each DRV could have 'm' TCS instances. Each TCS could have 'n' slots. Each
> +slot has a header (u32), address (u32), data (u32), status (u32) and a
> +read-response (u32). A TCS when triggered will send all the enabled commands
> +of the 'n' commands in that slot in sequence.
> +
> +A TCS may be triggered from Linux or triggered by the F/W after all the CPUs
> +have powered off to faciliate idle power saving. TCS could be classified as -
> +
> + SLEEP, /* Triggered by F/W */
> + WAKE, /* Triggered by F/W */
> + ACTIVE, /* Triggered by Linux */
> + CONTROL /* Triggered by F/W */
> +
> +The order in which they are described in the DT, should match the hardware
> +configuration.
> +
> +Requests can be made for the state of a resource, when the subsystem is active
> +or idle. When all subsystems like Modem, GPU, CPU are idle, the resource state
> +will be an aggregeate of the sleep votes from each of those subsystem. Drivers
> +may request a sleep value for their shared resources in addition to the active
> +mode requests.
> +
> +Control requests are instance specific requests that may or may not reach an
> +accelerator. Only one platform device in Linux can request a control channel
> +on a DRV.
> +
> +CONTROLLER:
> +----------
> +
> +PROPERTIES:
> +
> +- compatible:
> + Usage: required
> + Value type: <string>
> + Definition: Should be "qcom,rpmh-rsc".
> +
> +- reg:
> + Usage: required
> + Value type: <prop-encoded-array>
> + Definition: the first element specifies the base address of the DRV,
> + the second element specifies the size of the region.
> +
> +- interrupts:
> + Usage: required
> + Value type: <prop-encoded-interrupt>
> + Definition: the interrupt that trips when a message complete/response
> + is received for this DRV from the accelertors.
> +
> +- qcom,drv-id:
> + Usage: required
> + Value type: <u32>
> + Definition: the id of the DRV in the RSC block.
> +
> +- qcom, tcs-config:
^
space
> + Usage: required
> + Value type: <prop-encoded-array>
> + Definition: the tuple definining the configuration of TCS.
> + Must have 2 cells which describe each TCS type.
> + <type number_of_tcs>
> + - Cell #1 (TCS Type): TCS types can be specified -
> + SLEEP_TCS
> + WAKE_TCS
> + ACTIVE_TCS
> + CONTROL_TCS
These defines belong in this patch.
> + - Cell #2 (Number of TCS): <u32>
Is there some sort of range of numbers?
> +
> +- label:
> + Usage: optional
> + Value type: <string>
> + Definition: Name for the RSC. The name would be used in trace logs.
> +
> +Clients the want to use the RSC to communicate with RPMH would specify their
Clients the want?
> +bindings as child of the corresponding RSC controllers.
Need to be specific here about what the child nodes are.
> +
> +EXAMPLE 1:
> +
> +For a TCS whose RSC base address is is 0x179C0000 and is at a DRV of 2, the
> +register offsets for DRV2 start at 0D00, the register calculations are like
> +this -
> +First tuple: 0x179C0000 + 0x10000 * 2 = 0x179E0000
> +Second tuple: 0x179E0000 + 0xD00 = 0x179E0D00
> +
> + apps_rsc: rsc@179e000 {
> + compatible = "qcom,rpmh-rsc";
> + label = "apps_rsc";
> + reg = <0x179e0000 0x10000>, <0x179e0d00 0x3000>;
> + interrupts = <0 5 0>;
> + qcom,drv-id = <2>;
> + qcom,tcs-config = <SLEEP_TCS 3>,
> + <WAKE_TCS 3>,
> + <ACTIVE_TCS 2>,
> + <CONTROL_TCS 1>;
> +
> + foo-clk {
> + compatible = "foo-clk";
> + };
> + };
> +
> +EXAMPLE 2:
> +
> +For a TCS whose RSC base address is 0xAF20000 and is at DRV of 0, the register
> +offsets for DRV0 start at 01C00, the register calculations are like this -
> +First tuple: 0xAF20000
> +Second tuple: 0xAF20000 + 0x1C00
> +
> + disp_rsc: rsc@af20000 {
> + label = "disp_rsc";
> + compatible = "qcom,rpmh-rsc";
> + reg = <0xaf20000 0x10000>, <0xaf21c00 0x3000>;
> + interrupts = <0 129 0>;
> + qcom,drv-id = <0>;
> + qcom,tcs-config = <SLEEP_TCS 1>,
> + <WAKE_TCS 1>,
> + <ACTIVE_TCS 0>,
> + <CONTROL_TCS 1>;
> +
> + foo-clk {
> + compatible = "foo-clk";
> + };
> + };
> --
> The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum,
> a Linux Foundation Collaborative Project
>
> --
> To unsubscribe from this list: send the line "unsubscribe devicetree" in
> the body of a message to majordomo@vger.kernel.org
> More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply [flat|nested] 18+ messages in thread
* Re: [PATCH 2/4] dt-bindings: introduce RPMH RSC bindings for Qualcomm SoCs
2018-01-29 19:33 ` Rob Herring
@ 2018-01-30 16:24 ` Lina Iyer
0 siblings, 0 replies; 18+ messages in thread
From: Lina Iyer @ 2018-01-30 16:24 UTC (permalink / raw)
To: Rob Herring
Cc: andy.gross, david.brown, sboyd, rnayak, linux-arm-msm, linux-soc,
devicetree, linux-pm
Hi Rob,
On Mon, Jan 29 2018 at 19:33 +0000, Rob Herring wrote:
>On Thu, Jan 18, 2018 at 05:01:55PM -0700, Lina Iyer wrote:
>> Add device binding documentation for Qualcomm Technology Inc's RPMH RSC
>> driver. The hardware block is used for communicating resource state
>> requests for shared resources.
>>
>> Cc: devicetree@vger.kernel.org
>> Signed-off-by: Lina Iyer <ilina@codeaurora.org>
>> ---
>> .../devicetree/bindings/arm/msm/rpmh-rsc.txt | 134 +++++++++++++++++++++
>
>bindings/mailbox instead?
>
This doesn't use the mailbox framework, but is that still okay?
>> +- qcom,drv-id:
>> + Usage: required
>> + Value type: <u32>
>> + Definition: the id of the DRV in the RSC block.
>> +
>> +- qcom, tcs-config:
> ^
>space
>
Ok.
>> + Usage: required
>> + Value type: <prop-encoded-array>
>> + Definition: the tuple definining the configuration of TCS.
>> + Must have 2 cells which describe each TCS type.
>> + <type number_of_tcs>
>> + - Cell #1 (TCS Type): TCS types can be specified -
>> + SLEEP_TCS
>> + WAKE_TCS
>> + ACTIVE_TCS
>> + CONTROL_TCS
>
>These defines belong in this patch.
>
The defines are also used by the driver, so it ended up there to avoid
compilation errors. I guess I can make this patch a precursor to the
driver patch.
>> + - Cell #2 (Number of TCS): <u32>
>
>Is there some sort of range of numbers?
>
The range is limited by the area available and the complexity supported
by the processor. Generally 1-3 per TCS type.
>> +
>> +- label:
>> + Usage: optional
>> + Value type: <string>
>> + Definition: Name for the RSC. The name would be used in trace logs.
>> +
>> +Clients the want to use the RSC to communicate with RPMH would specify their
>
>Clients the want?
>
Argh! Will fix.
>> +bindings as child of the corresponding RSC controllers.
>
>Need to be specific here about what the child nodes are.
>
Ok. The child nodes are the clients that would want to use RPMH
communication.
Thanks,
Lina
^ permalink raw reply [flat|nested] 18+ messages in thread
* Re: [PATCH 2/4] dt-bindings: introduce RPMH RSC bindings for Qualcomm SoCs
2018-01-19 0:01 ` [PATCH 2/4] dt-bindings: introduce RPMH RSC bindings for Qualcomm SoCs Lina Iyer
2018-01-29 19:33 ` Rob Herring
@ 2018-02-03 19:11 ` Bjorn Andersson
1 sibling, 0 replies; 18+ messages in thread
From: Bjorn Andersson @ 2018-02-03 19:11 UTC (permalink / raw)
To: Lina Iyer
Cc: andy.gross, david.brown, sboyd, rnayak, linux-arm-msm, linux-soc,
devicetree, linux-pm
On Thu 18 Jan 16:01 PST 2018, Lina Iyer wrote:
> +- reg:
> + Usage: required
> + Value type: <prop-encoded-array>
> + Definition: the first element specifies the base address of the DRV,
> + the second element specifies the size of the region.
This doesn't capture the fact that there are two memory regions that
needs to be described.
[..]
> +- qcom, tcs-config:
> + Usage: required
> + Value type: <prop-encoded-array>
> + Definition: the tuple definining the configuration of TCS.
> + Must have 2 cells which describe each TCS type.
> + <type number_of_tcs>
I think this definition should capture that it's a list of tuples and
they are describing the functional allocation of the available TCSs.
> + - Cell #1 (TCS Type): TCS types can be specified -
> + SLEEP_TCS
> + WAKE_TCS
> + ACTIVE_TCS
> + CONTROL_TCS
> + - Cell #2 (Number of TCS): <u32>
> +
[..]
> +EXAMPLE 1:
> +
> +For a TCS whose RSC base address is is 0x179C0000 and is at a DRV of 2, the
> +register offsets for DRV2 start at 0D00, the register calculations are like
> +this -
> +First tuple: 0x179C0000 + 0x10000 * 2 = 0x179E0000
> +Second tuple: 0x179E0000 + 0xD00 = 0x179E0D00
So the first region is the DRV base and the second describe the TCSs? I
think that the purpose of the two regions should be clarified.
If this is the case then I would suggest also adding a
reg-names = "drv", "tcs";
in order to make the dts self-explaining.
> +
> + apps_rsc: rsc@179e000 {
> + compatible = "qcom,rpmh-rsc";
> + label = "apps_rsc";
> + reg = <0x179e0000 0x10000>, <0x179e0d00 0x3000>;
> + interrupts = <0 5 0>;
<GIC_SPI 5 IRQ_TYPE_LEVEL_HIGH>;
> + qcom,drv-id = <2>;
> + qcom,tcs-config = <SLEEP_TCS 3>,
> + <WAKE_TCS 3>,
> + <ACTIVE_TCS 2>,
> + <CONTROL_TCS 1>;
> +
> + foo-clk {
> + compatible = "foo-clk";
> + };
> + };
> +
Regards,
Bjorn
^ permalink raw reply [flat|nested] 18+ messages in thread
* [PATCH 3/4] drivers: qcom: rpmh-rsc: log RPMH requests in FTRACE
2018-01-19 0:01 [PATCH 0/4] drivers/qcom: add RPMH communication support Lina Iyer
2018-01-19 0:01 ` [PATCH 1/4] drivers: qcom: rpmh-rsc: add RPMH controller for QCOM SoCs Lina Iyer
2018-01-19 0:01 ` [PATCH 2/4] dt-bindings: introduce RPMH RSC bindings for Qualcomm SoCs Lina Iyer
@ 2018-01-19 0:01 ` Lina Iyer
[not found] ` <20180119000157.7380-4-ilina-sgV2jX0FEOL9JmXXK+q4OQ@public.gmane.org>
2018-01-19 0:01 ` [PATCH 4/4] drivers: qcom: rpmh: add RPMH helper functions Lina Iyer
3 siblings, 1 reply; 18+ messages in thread
From: Lina Iyer @ 2018-01-19 0:01 UTC (permalink / raw)
To: andy.gross, david.brown
Cc: sboyd, rnayak, linux-arm-msm, linux-soc, devicetree, linux-pm,
Lina Iyer, Steven Rostedt
Log sent RPMH requests and interrupt responses in FTRACE.
Cc: Steven Rostedt <rostedt@goodmis.org>
Signed-off-by: Lina Iyer <ilina@codeaurora.org>
---
drivers/soc/qcom/rpmh-rsc.c | 13 ++++++-
include/trace/events/rpmh.h | 89 +++++++++++++++++++++++++++++++++++++++++++++
2 files changed, 101 insertions(+), 1 deletion(-)
create mode 100644 include/trace/events/rpmh.h
diff --git a/drivers/soc/qcom/rpmh-rsc.c b/drivers/soc/qcom/rpmh-rsc.c
index 3e68cef5513e..424dc939b2e6 100644
--- a/drivers/soc/qcom/rpmh-rsc.c
+++ b/drivers/soc/qcom/rpmh-rsc.c
@@ -33,6 +33,9 @@
#include "rpmh-internal.h"
+#define CREATE_TRACE_POINTS
+#include <trace/events/rpmh.h>
+
#define MAX_CMDS_PER_TCS 16
#define MAX_TCS_PER_TYPE 3
@@ -325,6 +328,8 @@ static irqreturn_t tcs_irq_handler(int irq, void *p)
}
}
+ trace_rpmh_notify_irq(drv->name, m, resp->msg->payload[0].addr,
+ resp->err);
write_tcs_reg(base, RSC_DRV_CMD_ENABLE, m, 0, 0);
write_tcs_reg(base, RSC_DRV_IRQ_CLEAR, 0, 0, BIT(m));
atomic_set(&drv->tcs_in_use[m], 0);
@@ -351,7 +356,8 @@ static void tcs_notify_tx_done(unsigned long data)
struct rsc_drv *drv = (struct rsc_drv *)data;
struct tcs_response *resp;
unsigned long flags;
- int err;
+ int err, m;
+ struct tcs_mbox_msg *msg;
do {
spin_lock_irqsave(&drv->drv_lock, flags);
@@ -364,7 +370,10 @@ static void tcs_notify_tx_done(unsigned long data)
list_del(&resp->list);
spin_unlock_irqrestore(&drv->drv_lock, flags);
err = resp->err;
+ m = resp->m;
+ msg = resp->msg;
free_response(resp);
+ trace_rpmh_notify(drv->name, m, msg->payload[0].addr, err);
} while (1);
}
@@ -393,6 +402,8 @@ static void __tcs_buffer_write(struct rsc_drv *drv, int m, int n,
write_tcs_reg(base, RSC_DRV_CMD_MSGID, m, n + i, msgid);
write_tcs_reg(base, RSC_DRV_CMD_ADDR, m, n + i, cmd->addr);
write_tcs_reg(base, RSC_DRV_CMD_DATA, m, n + i, cmd->data);
+ trace_rpmh_send_msg(drv->name, m, n + i, msgid, cmd->addr,
+ cmd->data, cmd->complete);
}
write_tcs_reg(base, RSC_DRV_CMD_WAIT_FOR_CMPL, m, 0, cmd_complete);
diff --git a/include/trace/events/rpmh.h b/include/trace/events/rpmh.h
new file mode 100644
index 000000000000..2cc44fc5ff95
--- /dev/null
+++ b/include/trace/events/rpmh.h
@@ -0,0 +1,89 @@
+/* Copyright (c) 2016-2018, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#undef TRACE_SYSTEM
+#define TRACE_SYSTEM rpmh
+
+#if !defined(_TRACE_RPMH_H) || defined(TRACE_HEADER_MULTI_READ)
+#define _TRACE_RPMH_H
+
+#include <linux/tracepoint.h>
+
+DECLARE_EVENT_CLASS(rpmh_ack_recvd,
+
+ TP_PROTO(const char *s, int m, u32 addr, int errno),
+
+ TP_ARGS(s, m, addr, errno),
+
+ TP_STRUCT__entry(
+ __field(const char *, name)
+ __field(int, m)
+ __field(u32, addr)
+ __field(int, errno)
+ ),
+
+ TP_fast_assign(
+ __entry->name = s;
+ __entry->m = m;
+ __entry->addr = addr;
+ __entry->errno = errno;
+ ),
+
+ TP_printk("%s: ack: tcs-m:%d addr: 0x%08x errno: %d",
+ __entry->name, __entry->m, __entry->addr, __entry->errno)
+);
+
+DEFINE_EVENT(rpmh_ack_recvd, rpmh_notify_irq,
+ TP_PROTO(const char *s, int m, u32 addr, int err),
+ TP_ARGS(s, m, addr, err)
+);
+
+DEFINE_EVENT(rpmh_ack_recvd, rpmh_notify,
+ TP_PROTO(const char *s, int m, u32 addr, int err),
+ TP_ARGS(s, m, addr, err)
+);
+
+TRACE_EVENT(rpmh_send_msg,
+
+ TP_PROTO(const char *s, int m, int n, u32 h, u32 a, u32 v, bool c),
+
+ TP_ARGS(s, m, n, h, a, v, c),
+
+ TP_STRUCT__entry(
+ __field(const char*, name)
+ __field(int, m)
+ __field(int, n)
+ __field(u32, hdr)
+ __field(u32, addr)
+ __field(u32, data)
+ __field(bool, complete)
+ ),
+
+ TP_fast_assign(
+ __entry->name = s;
+ __entry->m = m;
+ __entry->n = n;
+ __entry->hdr = h;
+ __entry->addr = a;
+ __entry->data = v;
+ __entry->complete = c;
+ ),
+
+ TP_printk("%s: send-msg: tcs(m): %d cmd(n): %d msgid: 0x%08x addr: 0x%08x data: 0x%08x complete: %d",
+ __entry->name, __entry->m, __entry->n, __entry->hdr,
+ __entry->addr, __entry->data, __entry->complete)
+);
+
+#endif /* _TRACE_RPMH_H */
+
+#define TRACE_INCLUDE_FILE rpmh
+#include <trace/define_trace.h>
--
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum,
a Linux Foundation Collaborative Project
^ permalink raw reply related [flat|nested] 18+ messages in thread
* [PATCH 4/4] drivers: qcom: rpmh: add RPMH helper functions
2018-01-19 0:01 [PATCH 0/4] drivers/qcom: add RPMH communication support Lina Iyer
` (2 preceding siblings ...)
2018-01-19 0:01 ` [PATCH 3/4] drivers: qcom: rpmh-rsc: log RPMH requests in FTRACE Lina Iyer
@ 2018-01-19 0:01 ` Lina Iyer
2018-02-05 19:50 ` Bjorn Andersson
[not found] ` <20180119000157.7380-5-ilina-sgV2jX0FEOL9JmXXK+q4OQ@public.gmane.org>
3 siblings, 2 replies; 18+ messages in thread
From: Lina Iyer @ 2018-01-19 0:01 UTC (permalink / raw)
To: andy.gross, david.brown
Cc: sboyd, rnayak, linux-arm-msm, linux-soc, devicetree, linux-pm,
Lina Iyer
Sending RPMH requests and waiting for response from the controller
through a callback is common functionality across all platform drivers.
To simplify drivers, add a library functions to create RPMH client and
send resource state requests.
rpmh_write() is a synchronous blocking call that can be used to send
active state requests.
Signed-off-by: Lina Iyer <ilina@codeaurora.org>
---
drivers/soc/qcom/Makefile | 2 +-
drivers/soc/qcom/rpmh-internal.h | 2 +
drivers/soc/qcom/rpmh-rsc.c | 1 +
drivers/soc/qcom/rpmh.c | 264 +++++++++++++++++++++++++++++++++++++++
include/soc/qcom/rpmh.h | 41 ++++++
5 files changed, 309 insertions(+), 1 deletion(-)
create mode 100644 drivers/soc/qcom/rpmh.c
create mode 100644 include/soc/qcom/rpmh.h
diff --git a/drivers/soc/qcom/Makefile b/drivers/soc/qcom/Makefile
index b7951ce87663..0dba46387f1c 100644
--- a/drivers/soc/qcom/Makefile
+++ b/drivers/soc/qcom/Makefile
@@ -11,4 +11,4 @@ obj-$(CONFIG_QCOM_SMP2P) += smp2p.o
obj-$(CONFIG_QCOM_SMSM) += smsm.o
obj-$(CONFIG_QCOM_WCNSS_CTRL) += wcnss_ctrl.o
obj-$(CONFIG_QCOM_COMMAND_DB) += cmd-db.o
-obj-$(CONFIG_QCOM_RPMH) += rpmh-rsc.o
+obj-$(CONFIG_QCOM_RPMH) += rpmh-rsc.o rpmh.o
diff --git a/drivers/soc/qcom/rpmh-internal.h b/drivers/soc/qcom/rpmh-internal.h
index 0b482f788aa1..059637dcb55a 100644
--- a/drivers/soc/qcom/rpmh-internal.h
+++ b/drivers/soc/qcom/rpmh-internal.h
@@ -21,4 +21,6 @@ struct rsc_drv;
int rpmh_rsc_send_data(struct rsc_drv *drv, struct tcs_mbox_msg *msg);
+void rpmh_tx_done(struct tcs_mbox_msg *msg, int r);
+
#endif /* __RPM_INTERNAL_H__ */
diff --git a/drivers/soc/qcom/rpmh-rsc.c b/drivers/soc/qcom/rpmh-rsc.c
index 424dc939b2e6..e4f307c54567 100644
--- a/drivers/soc/qcom/rpmh-rsc.c
+++ b/drivers/soc/qcom/rpmh-rsc.c
@@ -374,6 +374,7 @@ static void tcs_notify_tx_done(unsigned long data)
msg = resp->msg;
free_response(resp);
trace_rpmh_notify(drv->name, m, msg->payload[0].addr, err);
+ rpmh_tx_done(msg, err);
} while (1);
}
diff --git a/drivers/soc/qcom/rpmh.c b/drivers/soc/qcom/rpmh.c
new file mode 100644
index 000000000000..ad1def2c362c
--- /dev/null
+++ b/drivers/soc/qcom/rpmh.c
@@ -0,0 +1,264 @@
+/* Copyright (c) 2016-2018, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ */
+
+#include <linux/atomic.h>
+#include <linux/interrupt.h>
+#include <linux/kernel.h>
+#include <linux/mailbox_client.h>
+#include <linux/module.h>
+#include <linux/of.h>
+#include <linux/platform_device.h>
+#include <linux/slab.h>
+#include <linux/types.h>
+#include <linux/wait.h>
+
+#include <soc/qcom/rpmh.h>
+
+#include "rpmh-internal.h"
+
+#define RPMH_MAX_MBOXES 2
+#define RPMH_TIMEOUT msecs_to_jiffies(10000)
+
+#define DEFINE_RPMH_MSG_ONSTACK(rc, s, q, c, name) \
+ struct rpmh_msg name = { \
+ .msg = { \
+ .state = s, \
+ .payload = name.cmd, \
+ .num_payload = 0, \
+ .is_complete = true, \
+ .invalidate = false, \
+ }, \
+ .cmd = { { 0 } }, \
+ .completion = q, \
+ .wait_count = c, \
+ .rc = rc, \
+ }
+
+/**
+ * rpmh_msg: the message to be sent to rpmh-rsc
+ *
+ * @msg: the request
+ * @cmd: the payload that will be part of the @msg
+ * @completion: triggered when request is done
+ * @wait_count: count of waiters for this completion
+ * @err: err return from the controller
+ */
+struct rpmh_msg {
+ struct tcs_mbox_msg msg;
+ struct tcs_cmd cmd[MAX_RPMH_PAYLOAD];
+ struct completion *completion;
+ atomic_t *wait_count;
+ struct rpmh_client *rc;
+ int err;
+};
+
+/**
+ * rpmh_ctrlr: our representation of the controller
+ *
+ * @drv: the controller instance
+ */
+struct rpmh_ctrlr {
+ struct rsc_drv *drv;
+};
+
+/**
+ * rpmh_client: the client object
+ *
+ * @dev: the platform device that is the owner
+ * @ctrlr: the controller associated with this client.
+ */
+struct rpmh_client {
+ struct device *dev;
+ struct rpmh_ctrlr *ctrlr;
+};
+
+static struct rpmh_ctrlr rpmh_rsc[RPMH_MAX_MBOXES];
+static DEFINE_MUTEX(rpmh_ctrlr_mutex);
+
+void rpmh_tx_done(struct tcs_mbox_msg *msg, int r)
+{
+ struct rpmh_msg *rpm_msg = container_of(msg, struct rpmh_msg, msg);
+ atomic_t *wc = rpm_msg->wait_count;
+ struct completion *compl = rpm_msg->completion;
+
+ rpm_msg->err = r;
+
+ if (r)
+ dev_err(rpm_msg->rc->dev,
+ "RPMH TX fail in msg addr 0x%x, err=%d\n",
+ rpm_msg->msg.payload[0].addr, r);
+
+ /* Signal the blocking thread we are done */
+ if (wc && atomic_dec_and_test(wc))
+ if (compl)
+ complete(compl);
+}
+EXPORT_SYMBOL(rpmh_tx_done);
+
+/**
+ * wait_for_tx_done: Wait until the response is received.
+ *
+ * @rc: The RPMH client
+ * @compl: The completion object
+ * @addr: An addr that we sent in that request
+ * @data: The data for the address in that request
+ *
+ */
+static inline int wait_for_tx_done(struct rpmh_client *rc,
+ struct completion *compl, u32 addr, u32 data)
+{
+ int ret;
+
+ ret = wait_for_completion_timeout(compl, RPMH_TIMEOUT);
+ if (ret)
+ dev_dbg(rc->dev,
+ "RPMH response received addr=0x%x data=0x%x\n",
+ addr, data);
+ else
+ dev_err(rc->dev,
+ "RPMH response timeout addr=0x%x data=0x%x\n",
+ addr, data);
+
+ return (ret > 0) ? 0 : -ETIMEDOUT;
+}
+
+/**
+ * __rpmh_write: send the RPMH request
+ *
+ * @rc: The RPMH client
+ * @state: Active/Sleep request type
+ * @rpm_msg: The data that needs to be sent (payload).
+ */
+int __rpmh_write(struct rpmh_client *rc, enum rpmh_state state,
+ struct rpmh_msg *rpm_msg)
+{
+ int ret = -EFAULT;
+
+ rpm_msg->msg.state = state;
+
+ if (state == RPMH_ACTIVE_ONLY_STATE) {
+ WARN_ON(irqs_disabled());
+ ret = rpmh_rsc_send_data(rc->ctrlr->drv, &rpm_msg->msg);
+ if (!ret)
+ dev_dbg(rc->dev,
+ "RPMH request sent addr=0x%x, data=0x%x\n",
+ rpm_msg->msg.payload[0].addr,
+ rpm_msg->msg.payload[0].data);
+ else
+ dev_warn(rc->dev,
+ "Error in RPMH request addr=0x%x, data=0x%x\n",
+ rpm_msg->msg.payload[0].addr,
+ rpm_msg->msg.payload[0].data);
+ }
+
+ return ret;
+}
+
+/**
+ * rpmh_write: Write a set of RPMH commands and block until response
+ *
+ * @rc: The RPMh handle got from rpmh_get_dev_channel
+ * @state: Active/sleep set
+ * @cmd: The payload data
+ * @n: The number of elements in payload
+ *
+ * May sleep. Do not call from atomic contexts.
+ */
+int rpmh_write(struct rpmh_client *rc, enum rpmh_state state,
+ struct tcs_cmd *cmd, int n)
+{
+ DECLARE_COMPLETION_ONSTACK(compl);
+ atomic_t wait_count = ATOMIC_INIT(1);
+ DEFINE_RPMH_MSG_ONSTACK(rc, state, &compl, &wait_count, rpm_msg);
+ int ret;
+
+ if (IS_ERR_OR_NULL(rc) || !cmd || n <= 0 || n > MAX_RPMH_PAYLOAD)
+ return -EINVAL;
+
+ might_sleep();
+
+ memcpy(rpm_msg.cmd, cmd, n * sizeof(*cmd));
+ rpm_msg.msg.num_payload = n;
+
+ ret = __rpmh_write(rc, state, &rpm_msg);
+ if (ret)
+ return ret;
+
+ return wait_for_tx_done(rc, &compl, cmd[0].addr, cmd[0].data);
+}
+EXPORT_SYMBOL(rpmh_write);
+
+static struct rpmh_ctrlr *get_rpmh_ctrlr(struct platform_device *pdev)
+{
+ int i;
+ struct rsc_drv *drv = dev_get_drvdata(pdev->dev.parent);
+ struct rpmh_ctrlr *ctrlr = ERR_PTR(-EFAULT);
+
+ if (!drv)
+ return ctrlr;
+
+ mutex_lock(&rpmh_ctrlr_mutex);
+ for (i = 0; i < RPMH_MAX_MBOXES; i++)
+ if (rpmh_rsc[i].drv == drv) {
+ ctrlr = &rpmh_rsc[i];
+ goto unlock;
+ }
+
+ if (i == RPMH_MAX_MBOXES)
+ for (i = 0; i < RPMH_MAX_MBOXES; i++)
+ if (rpmh_rsc[i].drv == NULL) {
+ ctrlr = &rpmh_rsc[i];
+ ctrlr->drv = drv;
+ break;
+ }
+unlock:
+ mutex_unlock(&rpmh_ctrlr_mutex);
+ return ctrlr;
+}
+
+/**
+ * rpmh_get_client: Get the RPMh handle
+ *
+ * @pdev: the platform device which needs to communicate with RPM
+ * accelerators
+ * May sleep.
+ */
+struct rpmh_client *rpmh_get_client(struct platform_device *pdev)
+{
+ struct rpmh_client *rc;
+
+ rc = kzalloc(sizeof(*rc), GFP_KERNEL);
+ if (!rc)
+ return ERR_PTR(-ENOMEM);
+
+ rc->dev = &pdev->dev;
+ rc->ctrlr = get_rpmh_ctrlr(pdev);
+ if (IS_ERR(rc->ctrlr)) {
+ kfree(rc);
+ return ERR_PTR(-EFAULT);
+ }
+
+ return rc;
+}
+EXPORT_SYMBOL(rpmh_get_client);
+
+/**
+ * rpmh_release: Release the RPMH client
+ *
+ * @rc: The RPMh handle to be freed.
+ */
+void rpmh_release(struct rpmh_client *rc)
+{
+ kfree(rc);
+}
+EXPORT_SYMBOL(rpmh_release);
diff --git a/include/soc/qcom/rpmh.h b/include/soc/qcom/rpmh.h
new file mode 100644
index 000000000000..bd1e316f0bbf
--- /dev/null
+++ b/include/soc/qcom/rpmh.h
@@ -0,0 +1,41 @@
+/* Copyright (c) 2016-2017, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ */
+#ifndef __SOC_QCOM_RPMH_H__
+#define __SOC_QCOM_RPMH_H__
+
+#include <soc/qcom/tcs.h>
+#include <linux/platform_device.h>
+
+struct rpmh_client;
+
+#ifdef CONFIG_QCOM_RPMH
+int rpmh_write(struct rpmh_client *rc, enum rpmh_state state,
+ struct tcs_cmd *cmd, int n);
+
+struct rpmh_client *rpmh_get_client(struct platform_device *pdev);
+
+void rpmh_release(struct rpmh_client *rc);
+
+#else
+
+static inline int rpmh_write(struct rpmh_client *rc, enum rpmh_state state,
+ struct tcs_cmd *cmd, int n)
+{ return -ENODEV; }
+
+struct rpmh_client *rpmh_get_client(struct platform_device *pdev)
+{ return ERR_PTR(-ENODEV); }
+
+static inline void rpmh_release(struct rpmh_client *rc) { }
+#endif /* CONFIG_QCOM_RPMH */
+
+#endif /* __SOC_QCOM_RPMH_H__ */
--
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum,
a Linux Foundation Collaborative Project
^ permalink raw reply related [flat|nested] 18+ messages in thread
* Re: [PATCH 4/4] drivers: qcom: rpmh: add RPMH helper functions
2018-01-19 0:01 ` [PATCH 4/4] drivers: qcom: rpmh: add RPMH helper functions Lina Iyer
@ 2018-02-05 19:50 ` Bjorn Andersson
2018-02-08 23:15 ` Lina Iyer
[not found] ` <20180119000157.7380-5-ilina-sgV2jX0FEOL9JmXXK+q4OQ@public.gmane.org>
1 sibling, 1 reply; 18+ messages in thread
From: Bjorn Andersson @ 2018-02-05 19:50 UTC (permalink / raw)
To: Lina Iyer
Cc: andy.gross, david.brown, sboyd, rnayak, linux-arm-msm, linux-soc,
devicetree, linux-pm
On Thu 18 Jan 16:01 PST 2018, Lina Iyer wrote:
> diff --git a/drivers/soc/qcom/Makefile b/drivers/soc/qcom/Makefile
> index b7951ce87663..0dba46387f1c 100644
> --- a/drivers/soc/qcom/Makefile
> +++ b/drivers/soc/qcom/Makefile
> @@ -11,4 +11,4 @@ obj-$(CONFIG_QCOM_SMP2P) += smp2p.o
> obj-$(CONFIG_QCOM_SMSM) += smsm.o
> obj-$(CONFIG_QCOM_WCNSS_CTRL) += wcnss_ctrl.o
> obj-$(CONFIG_QCOM_COMMAND_DB) += cmd-db.o
> -obj-$(CONFIG_QCOM_RPMH) += rpmh-rsc.o
> +obj-$(CONFIG_QCOM_RPMH) += rpmh-rsc.o rpmh.o
I think it would be better if you built these two objects into the same
module;
obj-$(CONFIG_QCOM_RPMH) += qcom_rpmh.o
qcom_rpmh-y += rpmh-rsc.o
qcom_rpmh-y += rpmh.o
> diff --git a/drivers/soc/qcom/rpmh-internal.h b/drivers/soc/qcom/rpmh-internal.h
[..]
> diff --git a/drivers/soc/qcom/rpmh.c b/drivers/soc/qcom/rpmh.c
[..]
> +#define RPMH_TIMEOUT msecs_to_jiffies(10000)
10 * HZ
> +
> +#define DEFINE_RPMH_MSG_ONSTACK(rc, s, q, c, name) \
> + struct rpmh_msg name = { \
> + .msg = { \
> + .state = s, \
> + .payload = name.cmd, \
> + .num_payload = 0, \
> + .is_complete = true, \
> + .invalidate = false, \
> + }, \
> + .cmd = { { 0 } }, \
> + .completion = q, \
> + .wait_count = c, \
> + .rc = rc, \
> + }
> +
> +/**
> + * rpmh_msg: the message to be sent to rpmh-rsc
> + *
> + * @msg: the request
> + * @cmd: the payload that will be part of the @msg
> + * @completion: triggered when request is done
> + * @wait_count: count of waiters for this completion
> + * @err: err return from the controller
> + */
> +struct rpmh_msg {
struct rpmh_request ?
> + struct tcs_mbox_msg msg;
> + struct tcs_cmd cmd[MAX_RPMH_PAYLOAD];
> + struct completion *completion;
> + atomic_t *wait_count;
When will @wait_count > 1? As far as I can see the only purpose would be
to be able to control whether you should complete @completion 0 or N
times; but 0 times is covered already by not specifying a @completion.
> + struct rpmh_client *rc;
> + int err;
> +};
> +
> +/**
> + * rpmh_ctrlr: our representation of the controller
> + *
> + * @drv: the controller instance
> + */
> +struct rpmh_ctrlr {
> + struct rsc_drv *drv;
Is this going to grow in the future? Otherwise just drop it and
reference the rsc_drv directly. (Even if it's growing it might be
cleaner to introduce it at that point)
> +};
> +
> +/**
> + * rpmh_client: the client object
> + *
> + * @dev: the platform device that is the owner
> + * @ctrlr: the controller associated with this client.
> + */
> +struct rpmh_client {
> + struct device *dev;
> + struct rpmh_ctrlr *ctrlr;
> +};
> +
> +static struct rpmh_ctrlr rpmh_rsc[RPMH_MAX_MBOXES];
> +static DEFINE_MUTEX(rpmh_ctrlr_mutex);
The client needs a reference to the rsc_drv, using the rpmh_ctrlr
abstraction and these global variables only seems to add unnecessary
complexity.
> +
> +void rpmh_tx_done(struct tcs_mbox_msg *msg, int r)
> +{
> + struct rpmh_msg *rpm_msg = container_of(msg, struct rpmh_msg, msg);
> + atomic_t *wc = rpm_msg->wait_count;
> + struct completion *compl = rpm_msg->completion;
> +
> + rpm_msg->err = r;
> +
> + if (r)
> + dev_err(rpm_msg->rc->dev,
> + "RPMH TX fail in msg addr 0x%x, err=%d\n",
> + rpm_msg->msg.payload[0].addr, r);
> +
> + /* Signal the blocking thread we are done */
> + if (wc && atomic_dec_and_test(wc))
> + if (compl)
> + complete(compl);
I think that you should drop this function and just complete
@rpm_msg->completion in the rcs driver.
> +}
> +EXPORT_SYMBOL(rpmh_tx_done);
> +
> +/**
> + * wait_for_tx_done: Wait until the response is received.
> + *
> + * @rc: The RPMH client
> + * @compl: The completion object
> + * @addr: An addr that we sent in that request
> + * @data: The data for the address in that request
> + *
> + */
> +static inline int wait_for_tx_done(struct rpmh_client *rc,
> + struct completion *compl, u32 addr, u32 data)
> +{
> + int ret;
> +
> + ret = wait_for_completion_timeout(compl, RPMH_TIMEOUT);
> + if (ret)
> + dev_dbg(rc->dev,
> + "RPMH response received addr=0x%x data=0x%x\n",
> + addr, data);
> + else
> + dev_err(rc->dev,
> + "RPMH response timeout addr=0x%x data=0x%x\n",
> + addr, data);
The request can contain a number of commands and these error messages
ends up printing the first one, on behalf of the client. I suspect that
this isn't useful enough in most cases, causing the client to print
another time.
I therefor suggest that you omit these prints.
> +
> + return (ret > 0) ? 0 : -ETIMEDOUT;
> +}
> +
> +/**
> + * __rpmh_write: send the RPMH request
> + *
> + * @rc: The RPMH client
> + * @state: Active/Sleep request type
> + * @rpm_msg: The data that needs to be sent (payload).
> + */
> +int __rpmh_write(struct rpmh_client *rc, enum rpmh_state state,
> + struct rpmh_msg *rpm_msg)
> +{
> + int ret = -EFAULT;
> +
> + rpm_msg->msg.state = state;
> +
> + if (state == RPMH_ACTIVE_ONLY_STATE) {
> + WARN_ON(irqs_disabled());
> + ret = rpmh_rsc_send_data(rc->ctrlr->drv, &rpm_msg->msg);
> + if (!ret)
> + dev_dbg(rc->dev,
> + "RPMH request sent addr=0x%x, data=0x%x\n",
> + rpm_msg->msg.payload[0].addr,
> + rpm_msg->msg.payload[0].data);
> + else
> + dev_warn(rc->dev,
> + "Error in RPMH request addr=0x%x, data=0x%x\n",
> + rpm_msg->msg.payload[0].addr,
> + rpm_msg->msg.payload[0].data);
Same thing here, for the user to be able to make sense of this error the
client will have to print something with more context. So I think you
should omit these too.
tracing failing addr/data pairs might make sense though!
> + }
> +
> + return ret;
> +}
> +
> +/**
> + * rpmh_write: Write a set of RPMH commands and block until response
> + *
> + * @rc: The RPMh handle got from rpmh_get_dev_channel
> + * @state: Active/sleep set
> + * @cmd: The payload data
> + * @n: The number of elements in payload
> + *
> + * May sleep. Do not call from atomic contexts.
> + */
> +int rpmh_write(struct rpmh_client *rc, enum rpmh_state state,
> + struct tcs_cmd *cmd, int n)
> +{
> + DECLARE_COMPLETION_ONSTACK(compl);
> + atomic_t wait_count = ATOMIC_INIT(1);
> + DEFINE_RPMH_MSG_ONSTACK(rc, state, &compl, &wait_count, rpm_msg);
> + int ret;
> +
> + if (IS_ERR_OR_NULL(rc) || !cmd || n <= 0 || n > MAX_RPMH_PAYLOAD)
> + return -EINVAL;
> +
> + might_sleep();
> +
> + memcpy(rpm_msg.cmd, cmd, n * sizeof(*cmd));
> + rpm_msg.msg.num_payload = n;
> +
> + ret = __rpmh_write(rc, state, &rpm_msg);
> + if (ret)
> + return ret;
> +
> + return wait_for_tx_done(rc, &compl, cmd[0].addr, cmd[0].data);
As you're returning here the completion object on the stack will be
trash, so you must inform rpmh_rsc that it may no longer complete it.
I suggest that you provide two functions in the rsc driver;
rpmh_rsc_send_sync() and rpmh_rsc_send_async(), and move the
wait-for-completion into the sync one. Also make the sync one return the
msg->err (and drop the tx_done cross-call).
(Or call them rpmh_rsc_send_wait() and rpmh_rsc_send_nowait())
> +}
> +EXPORT_SYMBOL(rpmh_write);
> +
> +static struct rpmh_ctrlr *get_rpmh_ctrlr(struct platform_device *pdev)
> +{
> + int i;
> + struct rsc_drv *drv = dev_get_drvdata(pdev->dev.parent);
> + struct rpmh_ctrlr *ctrlr = ERR_PTR(-EFAULT);
> +
> + if (!drv)
> + return ctrlr;
> +
> + mutex_lock(&rpmh_ctrlr_mutex);
> + for (i = 0; i < RPMH_MAX_MBOXES; i++)
> + if (rpmh_rsc[i].drv == drv) {
> + ctrlr = &rpmh_rsc[i];
> + goto unlock;
> + }
> +
> + if (i == RPMH_MAX_MBOXES)
> + for (i = 0; i < RPMH_MAX_MBOXES; i++)
> + if (rpmh_rsc[i].drv == NULL) {
> + ctrlr = &rpmh_rsc[i];
> + ctrlr->drv = drv;
> + break;
> + }
I fail to see the reason for tracking rsc_drv references in a global
array and try to find an existing one here. Just return the rsc_drv
acquired from dev_get_drvdata() to the caller.
> +unlock:
> + mutex_unlock(&rpmh_ctrlr_mutex);
> + return ctrlr;
> +}
> +
> +/**
> + * rpmh_get_client: Get the RPMh handle
> + *
> + * @pdev: the platform device which needs to communicate with RPM
> + * accelerators
> + * May sleep.
> + */
> +struct rpmh_client *rpmh_get_client(struct platform_device *pdev)
To make this analog to previous rpm drivers I think you should take the
device * of the parent here. I.e. client does:
rpmh = rpmh_get_client(&pdev->dev.parent).
I recognize that this removes the possibility of providing error
messages indicating which client caused the fault, but by above
suggestions these functions would be moved into the rsc driver; or the
error would be propagated to the client which could print these
themselves.
> +{
> + struct rpmh_client *rc;
> +
> + rc = kzalloc(sizeof(*rc), GFP_KERNEL);
> + if (!rc)
> + return ERR_PTR(-ENOMEM);
> +
> + rc->dev = &pdev->dev;
> + rc->ctrlr = get_rpmh_ctrlr(pdev);
> + if (IS_ERR(rc->ctrlr)) {
> + kfree(rc);
> + return ERR_PTR(-EFAULT);
> + }
> +
> + return rc;
> +}
> +EXPORT_SYMBOL(rpmh_get_client);
> +
> +/**
> + * rpmh_release: Release the RPMH client
> + *
> + * @rc: The RPMh handle to be freed.
> + */
> +void rpmh_release(struct rpmh_client *rc)
> +{
> + kfree(rc);
If you reduce above function to just return a rsc_drv reference you
don't even need a release function, which simplifies clients further.
> +}
> +EXPORT_SYMBOL(rpmh_release);
> diff --git a/include/soc/qcom/rpmh.h b/include/soc/qcom/rpmh.h
[..]
> +struct rpmh_client;
> +
> +#ifdef CONFIG_QCOM_RPMH
I think it would be fine to just make clients depend on QCOM_RPMH. If
you would prefer to get the compile testing in those drivers then make
this:
#if IS_ENABLED(CONFIG_QCOM_RPMH)
In case someone in the future decides to make RPMH tristate.
Regards,
Bjorn
^ permalink raw reply [flat|nested] 18+ messages in thread
* Re: [PATCH 4/4] drivers: qcom: rpmh: add RPMH helper functions
2018-02-05 19:50 ` Bjorn Andersson
@ 2018-02-08 23:15 ` Lina Iyer
0 siblings, 0 replies; 18+ messages in thread
From: Lina Iyer @ 2018-02-08 23:15 UTC (permalink / raw)
To: Bjorn Andersson
Cc: andy.gross, david.brown, sboyd, rnayak, linux-arm-msm, linux-soc,
devicetree, linux-pm
On Mon, Feb 05 2018 at 19:50 +0000, Bjorn Andersson wrote:
>On Thu 18 Jan 16:01 PST 2018, Lina Iyer wrote:
>> diff --git a/drivers/soc/qcom/Makefile b/drivers/soc/qcom/Makefile
>> index b7951ce87663..0dba46387f1c 100644
>> --- a/drivers/soc/qcom/Makefile
>> +++ b/drivers/soc/qcom/Makefile
>> @@ -11,4 +11,4 @@ obj-$(CONFIG_QCOM_SMP2P) += smp2p.o
>> obj-$(CONFIG_QCOM_SMSM) += smsm.o
>> obj-$(CONFIG_QCOM_WCNSS_CTRL) += wcnss_ctrl.o
>> obj-$(CONFIG_QCOM_COMMAND_DB) += cmd-db.o
>> -obj-$(CONFIG_QCOM_RPMH) += rpmh-rsc.o
>> +obj-$(CONFIG_QCOM_RPMH) += rpmh-rsc.o rpmh.o
>
>I think it would be better if you built these two objects into the same
>module;
>
>obj-$(CONFIG_QCOM_RPMH) += qcom_rpmh.o
>qcom_rpmh-y += rpmh-rsc.o
>qcom_rpmh-y += rpmh.o
>
Curious, how this would be better?
>> diff --git a/drivers/soc/qcom/rpmh-internal.h b/drivers/soc/qcom/rpmh-internal.h
>[..]
>> diff --git a/drivers/soc/qcom/rpmh.c b/drivers/soc/qcom/rpmh.c
>[..]
>> +#define RPMH_TIMEOUT msecs_to_jiffies(10000)
>
>10 * HZ
>
>> +
>> +#define DEFINE_RPMH_MSG_ONSTACK(rc, s, q, c, name) \
>> + struct rpmh_msg name = { \
>> + .msg = { \
>> + .state = s, \
>> + .payload = name.cmd, \
>> + .num_payload = 0, \
>> + .is_complete = true, \
>> + .invalidate = false, \
>> + }, \
>> + .cmd = { { 0 } }, \
>> + .completion = q, \
>> + .wait_count = c, \
>> + .rc = rc, \
>> + }
>> +
>> +/**
>> + * rpmh_msg: the message to be sent to rpmh-rsc
>> + *
>> + * @msg: the request
>> + * @cmd: the payload that will be part of the @msg
>> + * @completion: triggered when request is done
>> + * @wait_count: count of waiters for this completion
>> + * @err: err return from the controller
>> + */
>> +struct rpmh_msg {
>
>struct rpmh_request ?
>
Hmm.. ok.
>> + struct tcs_mbox_msg msg;
>> + struct tcs_cmd cmd[MAX_RPMH_PAYLOAD];
>> + struct completion *completion;
>> + atomic_t *wait_count;
>
>When will @wait_count > 1? As far as I can see the only purpose would be
>to be able to control whether you should complete @completion 0 or N
>times; but 0 times is covered already by not specifying a @completion.
>
There is a patch that I haven't posted in this series. It sends a batch
of requests instead of just 1. The wait count is equal to the number of
requests in that batch. Sorry it is a bit ahead of its real use. Adding
it later, increases unnecessary changes in the patches.
>> + struct rpmh_client *rc;
>> + int err;
>> +};
>> +
>> +/**
>> + * rpmh_ctrlr: our representation of the controller
>> + *
>> + * @drv: the controller instance
>> + */
>> +struct rpmh_ctrlr {
>> + struct rsc_drv *drv;
>
>Is this going to grow in the future? Otherwise just drop it and
>reference the rsc_drv directly. (Even if it's growing it might be
>cleaner to introduce it at that point)
>
Will grow :)
>> +};
>> +
>> +/**
>> + * rpmh_client: the client object
>> + *
>> + * @dev: the platform device that is the owner
>> + * @ctrlr: the controller associated with this client.
>> + */
>> +struct rpmh_client {
>> + struct device *dev;
>> + struct rpmh_ctrlr *ctrlr;
>> +};
>> +
>> +static struct rpmh_ctrlr rpmh_rsc[RPMH_MAX_MBOXES];
>> +static DEFINE_MUTEX(rpmh_ctrlr_mutex);
>
>The client needs a reference to the rsc_drv, using the rpmh_ctrlr
>abstraction and these global variables only seems to add unnecessary
>complexity.
>
There would be more functionality that needs these as structures and
a list of RSCs and therefore the global mutex and array.
Please bear with me on this.
>> +
>> +void rpmh_tx_done(struct tcs_mbox_msg *msg, int r)
>> +{
>> + struct rpmh_msg *rpm_msg = container_of(msg, struct rpmh_msg, msg);
>> + atomic_t *wc = rpm_msg->wait_count;
>> + struct completion *compl = rpm_msg->completion;
>> +
>> + rpm_msg->err = r;
>> +
>> + if (r)
>> + dev_err(rpm_msg->rc->dev,
>> + "RPMH TX fail in msg addr 0x%x, err=%d\n",
>> + rpm_msg->msg.payload[0].addr, r);
>> +
>> + /* Signal the blocking thread we are done */
>> + if (wc && atomic_dec_and_test(wc))
>> + if (compl)
>> + complete(compl);
>
>I think that you should drop this function and just complete
>@rpm_msg->completion in the rcs driver.
>
I am not sure how much of it I can upstream. Downstream I add more
functionality to this function to make it easier to debug on production.
If its not a bother I would like to keep it as is. Who knows, may be I
can get the debug code upstream.
>> +}
>> +EXPORT_SYMBOL(rpmh_tx_done);
>> +
>> +/**
>> + * wait_for_tx_done: Wait until the response is received.
>> + *
>> + * @rc: The RPMH client
>> + * @compl: The completion object
>> + * @addr: An addr that we sent in that request
>> + * @data: The data for the address in that request
>> + *
>> + */
>> +static inline int wait_for_tx_done(struct rpmh_client *rc,
>> + struct completion *compl, u32 addr, u32 data)
>> +{
>> + int ret;
>> +
>> + ret = wait_for_completion_timeout(compl, RPMH_TIMEOUT);
>> + if (ret)
>> + dev_dbg(rc->dev,
>> + "RPMH response received addr=0x%x data=0x%x\n",
>> + addr, data);
>> + else
>> + dev_err(rc->dev,
>> + "RPMH response timeout addr=0x%x data=0x%x\n",
>> + addr, data);
>
>The request can contain a number of commands and these error messages
>ends up printing the first one, on behalf of the client. I suspect that
>this isn't useful enough in most cases, causing the client to print
>another time.
>
>I therefor suggest that you omit these prints.
>
On the contrary, just the first address in the request is quite
sufficient to know what request failed. The rest of the requests in
dumped in the FTRACE while sending the request. That is enough to know
what was sent and correlate with what failed.
>> +
>> + return (ret > 0) ? 0 : -ETIMEDOUT;
>> +}
>> +
>> +/**
>> + * __rpmh_write: send the RPMH request
>> + *
>> + * @rc: The RPMH client
>> + * @state: Active/Sleep request type
>> + * @rpm_msg: The data that needs to be sent (payload).
>> + */
>> +int __rpmh_write(struct rpmh_client *rc, enum rpmh_state state,
>> + struct rpmh_msg *rpm_msg)
>> +{
>> + int ret = -EFAULT;
>> +
>> + rpm_msg->msg.state = state;
>> +
>> + if (state == RPMH_ACTIVE_ONLY_STATE) {
>> + WARN_ON(irqs_disabled());
>> + ret = rpmh_rsc_send_data(rc->ctrlr->drv, &rpm_msg->msg);
>> + if (!ret)
>> + dev_dbg(rc->dev,
>> + "RPMH request sent addr=0x%x, data=0x%x\n",
>> + rpm_msg->msg.payload[0].addr,
>> + rpm_msg->msg.payload[0].data);
>> + else
>> + dev_warn(rc->dev,
>> + "Error in RPMH request addr=0x%x, data=0x%x\n",
>> + rpm_msg->msg.payload[0].addr,
>> + rpm_msg->msg.payload[0].data);
>
>Same thing here, for the user to be able to make sense of this error the
>client will have to print something with more context. So I think you
>should omit these too.
>
>
>tracing failing addr/data pairs might make sense though!
>
See explanation above.
>> + }
>> +
>> + return ret;
>> +}
>> +
>> +/**
>> + * rpmh_write: Write a set of RPMH commands and block until response
>> + *
>> + * @rc: The RPMh handle got from rpmh_get_dev_channel
>> + * @state: Active/sleep set
>> + * @cmd: The payload data
>> + * @n: The number of elements in payload
>> + *
>> + * May sleep. Do not call from atomic contexts.
>> + */
>> +int rpmh_write(struct rpmh_client *rc, enum rpmh_state state,
>> + struct tcs_cmd *cmd, int n)
>> +{
>> + DECLARE_COMPLETION_ONSTACK(compl);
>> + atomic_t wait_count = ATOMIC_INIT(1);
>> + DEFINE_RPMH_MSG_ONSTACK(rc, state, &compl, &wait_count, rpm_msg);
>> + int ret;
>> +
>> + if (IS_ERR_OR_NULL(rc) || !cmd || n <= 0 || n > MAX_RPMH_PAYLOAD)
>> + return -EINVAL;
>> +
>> + might_sleep();
>> +
>> + memcpy(rpm_msg.cmd, cmd, n * sizeof(*cmd));
>> + rpm_msg.msg.num_payload = n;
>> +
>> + ret = __rpmh_write(rc, state, &rpm_msg);
>> + if (ret)
>> + return ret;
>> +
>> + return wait_for_tx_done(rc, &compl, cmd[0].addr, cmd[0].data);
>
>As you're returning here the completion object on the stack will be
>trash, so you must inform rpmh_rsc that it may no longer complete it.
>
>I suggest that you provide two functions in the rsc driver;
>rpmh_rsc_send_sync() and rpmh_rsc_send_async(), and move the
>wait-for-completion into the sync one. Also make the sync one return the
>msg->err (and drop the tx_done cross-call).
>
>(Or call them rpmh_rsc_send_wait() and rpmh_rsc_send_nowait())
>
This is the sync variant. The async variant follows this patch.
The wait_for_tx_done() is blocking and the compl object will not be
trashed until the completion is completed or it fails.
>> +}
>> +EXPORT_SYMBOL(rpmh_write);
>> +
>> +static struct rpmh_ctrlr *get_rpmh_ctrlr(struct platform_device *pdev)
>> +{
>> + int i;
>> + struct rsc_drv *drv = dev_get_drvdata(pdev->dev.parent);
>> + struct rpmh_ctrlr *ctrlr = ERR_PTR(-EFAULT);
>> +
>> + if (!drv)
>> + return ctrlr;
>> +
>> + mutex_lock(&rpmh_ctrlr_mutex);
>> + for (i = 0; i < RPMH_MAX_MBOXES; i++)
>> + if (rpmh_rsc[i].drv == drv) {
>> + ctrlr = &rpmh_rsc[i];
>> + goto unlock;
>> + }
>> +
>> + if (i == RPMH_MAX_MBOXES)
>> + for (i = 0; i < RPMH_MAX_MBOXES; i++)
>> + if (rpmh_rsc[i].drv == NULL) {
>> + ctrlr = &rpmh_rsc[i];
>> + ctrlr->drv = drv;
>> + break;
>> + }
>
>I fail to see the reason for tracking rsc_drv references in a global
>array and try to find an existing one here. Just return the rsc_drv
>acquired from dev_get_drvdata() to the caller.
>
There are multiple RSCs and clients would refer to one of them.
Future patches add information to the RSC as dictated by the client
(display driver is using the RSC) and therefore take action
accordingly.
>> +unlock:
>> + mutex_unlock(&rpmh_ctrlr_mutex);
>> + return ctrlr;
>> +}
>> +
>> +/**
>> + * rpmh_get_client: Get the RPMh handle
>> + *
>> + * @pdev: the platform device which needs to communicate with RPM
>> + * accelerators
>> + * May sleep.
>> + */
>> +struct rpmh_client *rpmh_get_client(struct platform_device *pdev)
>
>To make this analog to previous rpm drivers I think you should take the
>device * of the parent here. I.e. client does:
>
> rpmh = rpmh_get_client(&pdev->dev.parent).
>
>
>I recognize that this removes the possibility of providing error
>messages indicating which client caused the fault, but by above
>suggestions these functions would be moved into the rsc driver; or the
>error would be propagated to the client which could print these
>themselves.
>
I don't see a particular reason to be analogous with RPM. But, let me
think about it.
>> +{
>> + struct rpmh_client *rc;
>> +
>> + rc = kzalloc(sizeof(*rc), GFP_KERNEL);
>> + if (!rc)
>> + return ERR_PTR(-ENOMEM);
>> +
>> + rc->dev = &pdev->dev;
>> + rc->ctrlr = get_rpmh_ctrlr(pdev);
>> + if (IS_ERR(rc->ctrlr)) {
>> + kfree(rc);
>> + return ERR_PTR(-EFAULT);
>> + }
>> +
>> + return rc;
>> +}
>> +EXPORT_SYMBOL(rpmh_get_client);
>> +
>> +/**
>> + * rpmh_release: Release the RPMH client
>> + *
>> + * @rc: The RPMh handle to be freed.
>> + */
>> +void rpmh_release(struct rpmh_client *rc)
>> +{
>> + kfree(rc);
>
>If you reduce above function to just return a rsc_drv reference you
>don't even need a release function, which simplifies clients further.
>
Hmm.. not sure I understand. I need to release the allocated memory.
>> +}
>> +EXPORT_SYMBOL(rpmh_release);
>> diff --git a/include/soc/qcom/rpmh.h b/include/soc/qcom/rpmh.h
>[..]
>> +struct rpmh_client;
>> +
>> +#ifdef CONFIG_QCOM_RPMH
>
>I think it would be fine to just make clients depend on QCOM_RPMH. If
>you would prefer to get the compile testing in those drivers then make
>this:
>
>#if IS_ENABLED(CONFIG_QCOM_RPMH)
>
>In case someone in the future decides to make RPMH tristate.
>
OK.
Thanks,
Lina
^ permalink raw reply [flat|nested] 18+ messages in thread
[parent not found: <20180119000157.7380-5-ilina-sgV2jX0FEOL9JmXXK+q4OQ@public.gmane.org>]
* Re: [PATCH 4/4] drivers: qcom: rpmh: add RPMH helper functions
[not found] ` <20180119000157.7380-5-ilina-sgV2jX0FEOL9JmXXK+q4OQ@public.gmane.org>
@ 2018-02-15 8:49 ` Rajendra Nayak
2018-02-15 15:52 ` Lina Iyer
0 siblings, 1 reply; 18+ messages in thread
From: Rajendra Nayak @ 2018-02-15 8:49 UTC (permalink / raw)
To: Lina Iyer, andy.gross-QSEj5FYQhm4dnm+yROfE0A,
david.brown-QSEj5FYQhm4dnm+yROfE0A
Cc: sboyd-sgV2jX0FEOL9JmXXK+q4OQ,
linux-arm-msm-u79uwXL29TY76Z2rM5mHXA,
linux-soc-u79uwXL29TY76Z2rM5mHXA,
devicetree-u79uwXL29TY76Z2rM5mHXA,
linux-pm-u79uwXL29TY76Z2rM5mHXA
[]..
> diff --git a/drivers/soc/qcom/rpmh.c b/drivers/soc/qcom/rpmh.c
> new file mode 100644
> index 000000000000..ad1def2c362c
> --- /dev/null
> +++ b/drivers/soc/qcom/rpmh.c
> @@ -0,0 +1,264 @@
> +/* Copyright (c) 2016-2018, The Linux Foundation. All rights reserved.
> + *
> + * This program is free software; you can redistribute it and/or modify
> + * it under the terms of the GNU General Public License version 2 and
> + * only version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful,
> + * but WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
> + * GNU General Public License for more details.
> + *
> + */
> +
> +#include <linux/atomic.h>
> +#include <linux/interrupt.h>
> +#include <linux/kernel.h>
> +#include <linux/mailbox_client.h>
> +#include <linux/module.h>
> +#include <linux/of.h>
> +#include <linux/platform_device.h>
> +#include <linux/slab.h>
> +#include <linux/types.h>
> +#include <linux/wait.h>
> +
> +#include <soc/qcom/rpmh.h>
> +
> +#include "rpmh-internal.h"
> +
> +#define RPMH_MAX_MBOXES 2
> +#define RPMH_TIMEOUT msecs_to_jiffies(10000)
> +
> +#define DEFINE_RPMH_MSG_ONSTACK(rc, s, q, c, name)
> + struct rpmh_msg name = { \
> + .msg = { \
> + .state = s, \
> + .payload = name.cmd, \
> + .num_payload = 0, \
> + .is_complete = true, \
> + .invalidate = false, \
There seems to be no field called 'invalidate' as part of the struct
--
Qualcomm Innovation Center, Inc. is a member of Code Aurora Forum,
hosted by The Linux Foundation
--
To unsubscribe from this list: send the line "unsubscribe devicetree" in
the body of a message to majordomo-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply [flat|nested] 18+ messages in thread
* Re: [PATCH 4/4] drivers: qcom: rpmh: add RPMH helper functions
2018-02-15 8:49 ` Rajendra Nayak
@ 2018-02-15 15:52 ` Lina Iyer
0 siblings, 0 replies; 18+ messages in thread
From: Lina Iyer @ 2018-02-15 15:52 UTC (permalink / raw)
To: Rajendra Nayak
Cc: andy.gross, david.brown, sboyd, linux-arm-msm, linux-soc,
devicetree, linux-pm
On Thu, Feb 15 2018 at 08:49 +0000, Rajendra Nayak wrote:
>[]..
>
>> diff --git a/drivers/soc/qcom/rpmh.c b/drivers/soc/qcom/rpmh.c
>> new file mode 100644
>> index 000000000000..ad1def2c362c
>> --- /dev/null
>> +++ b/drivers/soc/qcom/rpmh.c
>> @@ -0,0 +1,264 @@
>> +/* Copyright (c) 2016-2018, The Linux Foundation. All rights reserved.
>> + *
>> + * This program is free software; you can redistribute it and/or modify
>> + * it under the terms of the GNU General Public License version 2 and
>> + * only version 2 as published by the Free Software Foundation.
>> + *
>> + * This program is distributed in the hope that it will be useful,
>> + * but WITHOUT ANY WARRANTY; without even the implied warranty of
>> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
>> + * GNU General Public License for more details.
>> + *
>> + */
>> +
>> +#include <linux/atomic.h>
>> +#include <linux/interrupt.h>
>> +#include <linux/kernel.h>
>> +#include <linux/mailbox_client.h>
>> +#include <linux/module.h>
>> +#include <linux/of.h>
>> +#include <linux/platform_device.h>
>> +#include <linux/slab.h>
>> +#include <linux/types.h>
>> +#include <linux/wait.h>
>> +
>> +#include <soc/qcom/rpmh.h>
>> +
>> +#include "rpmh-internal.h"
>> +
>> +#define RPMH_MAX_MBOXES 2
>> +#define RPMH_TIMEOUT msecs_to_jiffies(10000)
>> +
>> +#define DEFINE_RPMH_MSG_ONSTACK(rc, s, q, c, name)
>> + struct rpmh_msg name = { \
>> + .msg = { \
>> + .state = s, \
>> + .payload = name.cmd, \
>> + .num_payload = 0, \
>> + .is_complete = true, \
>> + .invalidate = false, \
>
>There seems to be no field called 'invalidate' as part of the struct
>
Yup. Sorry, I will remove it in the next revision. I should be posting
one in a day or so.
Thanks,
Lina
^ permalink raw reply [flat|nested] 18+ messages in thread