QCOM QRC device driver is used for Robotic SDK MCU
[commit]misc: qualcomm: QRC driver for Robotic SDK MCU
This commit is used to enable robotic controller device driver.
QRC Driver support functions:
- Read data from serial device port.
- Write data to serial device port.
- Pin control reset robotic controller.
[commit]dt-bindings: misc: merge qcom,qrc
This commit is used to support qcom qrc devicetree binding.
Signed-off-by: Canfeng Zhuang <[email protected]>
---
Canfeng Zhuang (2):
misc: qualcomm: QRC driver for Robotic SDK MCU
dt-bindings: misc: merge qcom,qrc
.../devicetree/bindings/misc/qcom,qrc.yaml | 32 ++
drivers/misc/Kconfig | 1 +
drivers/misc/Makefile | 1 +
drivers/misc/qrc/Kconfig | 16 +
drivers/misc/qrc/Makefile | 6 +
drivers/misc/qrc/qrc_core.c | 336 ++++++++++++++++++++
drivers/misc/qrc/qrc_core.h | 143 +++++++++
drivers/misc/qrc/qrc_uart.c | 345 +++++++++++++++++++++
8 files changed, 880 insertions(+)
---
base-commit: 805d849d7c3cc1f38efefd48b2480d62b7b5dcb7
change-id: 20240304-qcom_qrc-778c8fad8846
Best regards,
--
Canfeng Zhuang <[email protected]>
Merge Qualcomm-specific qrc binding
Signed-off-by: Canfeng Zhuang <[email protected]>
---
.../devicetree/bindings/misc/qcom,qrc.yaml | 32 ++++++++++++++++++++++
1 file changed, 32 insertions(+)
diff --git a/Documentation/devicetree/bindings/misc/qcom,qrc.yaml b/Documentation/devicetree/bindings/misc/qcom,qrc.yaml
new file mode 100644
index 000000000000..730efd679ba0
--- /dev/null
+++ b/Documentation/devicetree/bindings/misc/qcom,qrc.yaml
@@ -0,0 +1,32 @@
+# SPDX-License-Identifier: (GPL-2.0-only OR BSD-2-Clause)
+%YAML 1.2
+---
+$id: http://devicetree.org/schemas/misc/qcom,qrc.yaml#
+$schema: http://devicetree.org/meta-schemas/core.yaml#
+
+title: Qualcomm Robotics Communication Driver
+
+maintainers:
+ - Srinivas Kandagatla <[email protected]>
+
+description: |
+ The QRC (Qualcomm Robotics Communication) driver is used for information interaction
+ between the robot control board and the main board when using a uart port connection.
+ This Driver will support uart read & write and robot control board
+ reset function.
+
+properties:
+ compatible:
+ const: qcom,qrc-uart
+
+required:
+ - compatible
+
+additionalProperties: false
+
+examples:
+ - |
+ qrc: qcom,qrc_uart {
+ compatible = "qcom,qrc-uart";
+ };
+
--
2.25.1
QRC Driver support functions:
- Read data from serial device port.
- Write data to serial device port.
- Pin control reset robotic controller.
Signed-off-by: Canfeng Zhuang <[email protected]>
---
drivers/misc/Kconfig | 1 +
drivers/misc/Makefile | 1 +
drivers/misc/qrc/Kconfig | 16 ++
drivers/misc/qrc/Makefile | 6 +
drivers/misc/qrc/qrc_core.c | 336 ++++++++++++++++++++++++++++++++++++++++++
drivers/misc/qrc/qrc_core.h | 143 ++++++++++++++++++
drivers/misc/qrc/qrc_uart.c | 345 ++++++++++++++++++++++++++++++++++++++++++++
7 files changed, 848 insertions(+)
diff --git a/drivers/misc/Kconfig b/drivers/misc/Kconfig
index 4fb291f0bf7c..a43108af6fde 100644
--- a/drivers/misc/Kconfig
+++ b/drivers/misc/Kconfig
@@ -591,4 +591,5 @@ source "drivers/misc/cardreader/Kconfig"
source "drivers/misc/uacce/Kconfig"
source "drivers/misc/pvpanic/Kconfig"
source "drivers/misc/mchp_pci1xxxx/Kconfig"
+source "drivers/misc/qrc/Kconfig"
endmenu
diff --git a/drivers/misc/Makefile b/drivers/misc/Makefile
index ea6ea5bbbc9c..ab3b2c4d99fa 100644
--- a/drivers/misc/Makefile
+++ b/drivers/misc/Makefile
@@ -68,3 +68,4 @@ obj-$(CONFIG_TMR_INJECT) += xilinx_tmr_inject.o
obj-$(CONFIG_TPS6594_ESM) += tps6594-esm.o
obj-$(CONFIG_TPS6594_PFSM) += tps6594-pfsm.o
obj-$(CONFIG_NSM) += nsm.o
+obj-$(CONFIG_QCOM_QRC) += qrc/
diff --git a/drivers/misc/qrc/Kconfig b/drivers/misc/qrc/Kconfig
new file mode 100644
index 000000000000..994985d7c320
--- /dev/null
+++ b/drivers/misc/qrc/Kconfig
@@ -0,0 +1,16 @@
+# SPDX-License-Identifier: GPL-2.0-only
+#
+# QRC device driver configuration
+#
+
+menu "QCOM QRC device driver"
+
+config QCOM_QRC
+ tristate "QCOM QRC device driver for Robotic SDK MCU"
+ help
+ This kernel configuration is used to enable robotic controller
+ device driver. Say M here if you want to enable robotic
+ controller device driver.
+ When in doubt, say N.
+
+endmenu
diff --git a/drivers/misc/qrc/Makefile b/drivers/misc/qrc/Makefile
new file mode 100644
index 000000000000..da2cf81f3c59
--- /dev/null
+++ b/drivers/misc/qrc/Makefile
@@ -0,0 +1,6 @@
+# SPDX-License-Identifier: GPL-2.0-only
+#
+# Makefile for the QRC bus specific drivers.
+
+
+obj-$(CONFIG_QCOM_QRC) += qrc_core.o qrc_uart.o
diff --git a/drivers/misc/qrc/qrc_core.c b/drivers/misc/qrc/qrc_core.c
new file mode 100644
index 000000000000..5cedb050dac4
--- /dev/null
+++ b/drivers/misc/qrc/qrc_core.c
@@ -0,0 +1,336 @@
+// SPDX-License-Identifier: GPL-2.0-only
+/* driver/misc/qrc/qrc_core.c
+ *
+ * Copyright (c) 2022-2023 Qualcomm Innovation Center, Inc. All rights reserved.
+ */
+
+#include <linux/module.h>
+#include <linux/types.h>
+#include <linux/sched.h>
+#include <linux/init.h>
+#include <linux/cdev.h>
+#include <linux/slab.h>
+#include <linux/poll.h>
+#include <linux/platform_device.h>
+#include <linux/of_device.h>
+#include <linux/of.h>
+#include <linux/of_gpio.h>
+#include <linux/gpio.h>
+#include <linux/delay.h>
+
+#include "qrc_core.h"
+
+#define QRC_DEVICE_NAME "qrc"
+
+static dev_t qrc_devt;
+static struct class *qrc_class;
+
+static int qrc_cdev_fasync(int fd, struct file *filp, int mode)
+{
+ struct qrc_dev *qrc;
+
+ qrc = filp->private_data;
+ return fasync_helper(fd, filp, mode, &qrc->async_queue);
+}
+
+static int qrc_cdev_open(struct inode *inode, struct file *filp)
+{
+ struct qrc_dev *qrc;
+
+ qrc = container_of(inode->i_cdev, struct qrc_dev, cdev);
+ filp->private_data = qrc;
+ if (qrc->qrc_ops)
+ qrc->qrc_ops->qrcops_open(qrc);
+ return 0;
+}
+
+static int qrc_cdev_release(struct inode *inode, struct file *filp)
+{
+ struct qrc_dev *qrc;
+
+ qrc = filp->private_data;
+ if (qrc->qrc_ops)
+ qrc->qrc_ops->qrcops_close(qrc);
+
+ return 0;
+}
+
+/* GPIO control */
+static int
+qrc_control_gpio_init(struct qrc_dev *qdev, struct device_node *node)
+{
+ int ret;
+ struct gpio_desc *qrc_boot0_gpiod;
+ struct gpio_desc *qrc_reset_gpiod;
+
+ /* QRC BOOT0 GPIO */
+ qdev->qrc_boot0_gpio = of_get_named_gpio(node,
+ "qcom,qrc-boot-gpio", 0);
+ if (qdev->qrc_boot0_gpio < 0)
+ dev_err(qdev->dev, "qrc_boot0_gpio is not available\n");
+
+ /* UART RESET GPIO */
+ qdev->qrc_reset_gpio = of_get_named_gpio(node,
+ "qcom,qrc-reset-gpio", 0);
+ if (qdev->qrc_reset_gpio < 0)
+ dev_err(qdev->dev, "qrc_reset_gpio is not available\n");
+
+ if (gpio_is_valid(qdev->qrc_boot0_gpio)) {
+ ret = gpio_request(qdev->qrc_boot0_gpio, "QRC_BOOT0_GPIO");
+ if (ret) {
+ dev_err(qdev->dev, "gpio request qrc_boot0_gpio failed for:%d\n",
+ qdev->qrc_boot0_gpio);
+ return ret;
+ }
+
+ ret = gpio_direction_output(qdev->qrc_boot0_gpio, 1);
+ qrc_boot0_gpiod = gpio_to_desc(qdev->qrc_boot0_gpio);
+ ret += gpiod_export(qrc_boot0_gpiod, 0);
+ if (ret) {
+ dev_err(qdev->dev, "Unable to configure GPIO%d (BOOT0)\n",
+ qdev->qrc_boot0_gpio);
+ ret = -EBUSY;
+ gpio_free(qdev->qrc_boot0_gpio);
+ return ret;
+ }
+
+ /* default config gpio status.boot=1 */
+ gpio_set_value(qdev->qrc_boot0_gpio, 1);
+ }
+
+ if (gpio_is_valid(qdev->qrc_reset_gpio)) {
+ ret = gpio_request(qdev->qrc_reset_gpio, "QRC_RESET_GPIO");
+ if (ret) {
+ dev_err(qdev->dev, "gpio request qrc_reset_gpio failed for:%d\n",
+ qdev->qrc_reset_gpio);
+ return ret;
+ }
+
+ ret = gpio_direction_output(qdev->qrc_reset_gpio, 0);
+ qrc_reset_gpiod = gpio_to_desc(qdev->qrc_reset_gpio);
+ ret += gpiod_export(qrc_reset_gpiod, 0);
+
+ if (ret) {
+ dev_err(qdev->dev, "Unable to configure GPIO%d (RESET)\n",
+ qdev->qrc_reset_gpio);
+ ret = -EBUSY;
+ gpio_free(qdev->qrc_reset_gpio);
+ return ret;
+ }
+
+ /* default config gpio status.reset=0 */
+ gpio_set_value(qdev->qrc_reset_gpio, 0);
+ }
+
+ return 0;
+}
+
+static void
+qrc_control_gpio_uninit(struct qrc_dev *qdev)
+{
+ if (gpio_is_valid(qdev->qrc_boot0_gpio))
+ gpio_free(qdev->qrc_boot0_gpio);
+
+ if (gpio_is_valid(qdev->qrc_reset_gpio))
+ gpio_free(qdev->qrc_reset_gpio);
+}
+
+static void qrc_gpio_reboot(struct qrc_dev *qdev)
+{
+ gpio_set_value(qdev->qrc_reset_gpio, 1);
+ msleep(100);
+ gpio_set_value(qdev->qrc_reset_gpio, 0);
+}
+
+static long qrc_cdev_ioctl(struct file *filp, unsigned int cmd,
+ unsigned long arg)
+{
+ struct qrc_dev *qdev;
+ void __user *argp = (void __user *)arg;
+ unsigned int readable_size;
+
+ qdev = filp->private_data;
+ switch (cmd) {
+ case QRC_FIFO_CLEAR:
+ mutex_lock(&qdev->mutex);
+ qdev->qrc_ops->qrcops_data_clean(qdev);
+ mutex_unlock(&qdev->mutex);
+ return 0;
+ case QRC_REBOOT:
+ if (gpio_is_valid(qdev->qrc_reset_gpio)) {
+ qrc_gpio_reboot(qdev);
+ return 0;
+ } else {
+ return -EFAULT;
+ }
+ case QRC_BOOT_TO_MEM:
+ if (gpio_is_valid(qdev->qrc_boot0_gpio)) {
+ gpio_set_value(qdev->qrc_boot0_gpio, 1);
+ qrc_gpio_reboot(qdev);
+ return 0;
+ } else {
+ return -EFAULT;
+ }
+ case QRC_BOOT_TO_FLASH:
+ if (gpio_is_valid(qdev->qrc_boot0_gpio)) {
+ gpio_set_value(qdev->qrc_boot0_gpio, 0);
+ qrc_gpio_reboot(qdev);
+ return 0;
+ } else {
+ return -EFAULT;
+ }
+ case QRC_FIONREAD:
+ readable_size = qdev->qrc_ops->qrcops_data_status(qdev);
+ if (copy_to_user(argp, &readable_size, sizeof(unsigned int))) {
+ dev_err(qdev->dev, "copy_to_user failed\n");
+ return -EFAULT;
+ }
+ return 0;
+ default:
+ return -EINVAL;
+ }
+}
+
+static unsigned int qrc_cdev_poll(struct file *filp, poll_table *wait)
+{
+ unsigned int mask = 0;
+ struct qrc_dev *qrc;
+
+ qrc = filp->private_data;
+ mutex_lock(&qrc->mutex);
+
+ poll_wait(filp, &qrc->r_wait, wait);
+
+ if (qrc->qrc_ops->qrcops_data_status(qrc) != 0)
+ mask |= POLLIN | POLLRDNORM;
+
+ mutex_unlock(&qrc->mutex);
+ return mask;
+}
+
+static ssize_t qrc_cdev_read(struct file *filp, char __user *buf,
+ size_t count, loff_t *ppos)
+{
+ int ret;
+ struct qrc_dev *qrc;
+ DECLARE_WAITQUEUE(wait, current);
+
+ qrc = filp->private_data;
+
+ mutex_lock(&qrc->mutex);
+ add_wait_queue(&qrc->r_wait, &wait);
+
+ while (qrc->qrc_ops->qrcops_data_status(qrc) == 0) {
+ if (filp->f_flags & O_NONBLOCK) {
+ ret = -EAGAIN;
+ goto out;
+ }
+ __set_current_state(TASK_INTERRUPTIBLE);
+ mutex_unlock(&qrc->mutex);
+
+ schedule();
+ if (signal_pending(current)) {
+ ret = -ERESTARTSYS;
+ goto remove;
+ }
+
+ mutex_lock(&qrc->mutex);
+ }
+
+ ret = qrc->qrc_ops->qrcops_receive(qrc, buf, count);
+
+out:
+ mutex_unlock(&qrc->mutex);
+remove:
+ remove_wait_queue(&qrc->r_wait, &wait);
+ set_current_state(TASK_RUNNING);
+ return ret;
+}
+
+static ssize_t qrc_cdev_write(struct file *filp, const char __user *buf,
+ size_t count, loff_t *ppos)
+{
+ struct qrc_dev *qrc;
+ enum qrcdev_tx ret;
+
+ qrc = filp->private_data;
+ ret = qrc->qrc_ops->qrcops_xmit(buf, count, qrc);
+ if (ret == QRCDEV_TX_OK)
+ return count;
+
+ return 0;
+}
+
+static const struct file_operations qrc_cdev_fops = {
+ .owner = THIS_MODULE,
+ .read = qrc_cdev_read,
+ .write = qrc_cdev_write,
+ .unlocked_ioctl = qrc_cdev_ioctl,
+ .poll = qrc_cdev_poll,
+ .fasync = qrc_cdev_fasync,
+ .open = qrc_cdev_open,
+ .release = qrc_cdev_release,
+};
+
+/*-------Interface for qrc device ---------*/
+int qrc_register_device(struct qrc_dev *qdev, struct device *dev)
+{
+ int ret;
+ dev_t devt;
+
+ if (!qdev)
+ return -ENOMEM;
+
+ mutex_init(&qdev->mutex);
+ init_waitqueue_head(&qdev->r_wait);
+ init_waitqueue_head(&qdev->w_wait);
+
+ /*register cdev*/
+ qrc_class = class_create("qrc_class");
+ if (IS_ERR(qrc_class)) {
+ dev_err(dev, "failed to allocate class\n");
+ return PTR_ERR(qrc_class);
+ }
+ ret = alloc_chrdev_region(&qrc_devt, 0, 1, "qrc");
+ if (ret < 0) {
+ dev_err(dev, "failed to allocate char device region\n");
+ class_destroy(qrc_class);
+ return ret;
+ }
+
+ devt = MKDEV(MAJOR(qrc_devt), 0);
+
+ cdev_init(&qdev->cdev, &qrc_cdev_fops);
+ ret = qrc_control_gpio_init(qdev, dev->of_node);
+
+ ret = cdev_add(&qdev->cdev, devt, 1);
+ if (ret) {
+ dev_err(dev, "qrc failed to add char device\n");
+ return ret;
+ }
+
+ qdev->dev = device_create(qrc_class, dev, devt, qdev,
+ "qrc");
+ if (IS_ERR(qdev->dev)) {
+ ret = PTR_ERR(qdev->dev);
+ goto del_cdev;
+ }
+
+ return 0;
+
+del_cdev:
+ cdev_del(&qdev->cdev);
+ return ret;
+}
+EXPORT_SYMBOL_GPL(qrc_register_device);
+
+void qrc_unregister(struct qrc_dev *qdev)
+{
+ device_destroy(qrc_class, qdev->dev->devt);
+ qrc_control_gpio_uninit(qdev);
+ dev_err(qdev->dev, "qrc drv unregistered\n");
+}
+EXPORT_SYMBOL_GPL(qrc_unregister);
+
+MODULE_DESCRIPTION("Qualcomm Technologies, Inc. QRC Uart Driver");
+MODULE_LICENSE("GPL");
diff --git a/drivers/misc/qrc/qrc_core.h b/drivers/misc/qrc/qrc_core.h
new file mode 100644
index 000000000000..398343e43cfa
--- /dev/null
+++ b/drivers/misc/qrc/qrc_core.h
@@ -0,0 +1,143 @@
+/* SPDX-License-Identifier: GPL-2.0-only */
+/* driver/misc/qrc/qrc_core.h
+ *
+ * Copyright (c) 2022-2023 Qualcomm Innovation Center, Inc. All rights reserved.
+ */
+
+#ifndef _QRC_CORE_H
+#define _QRC_CORE_H
+
+#include <linux/sched.h>
+#include <linux/types.h>
+#include <linux/cdev.h>
+#include <linux/device.h>
+#include <linux/kfifo.h>
+#include <linux/sched/signal.h>
+#include <linux/uaccess.h>
+#include <linux/ioctl.h>
+
+#define QRC_NAME_SIZE 30
+#define QRC_INTERFACE_SIZE 30
+#define QRC_FIFO_SIZE 0x1000
+
+struct qrc_dev;
+
+/* IOCTL commands */
+#define QRC_IOC_MAGIC 'q'
+
+/* Clear read fifo */
+#define QRC_FIFO_CLEAR _IO(QRC_IOC_MAGIC, 1)
+/* Reboot QRC controller */
+#define QRC_REBOOT _IO(QRC_IOC_MAGIC, 2)
+/* QRC boot from memory */
+#define QRC_BOOT_TO_MEM _IO(QRC_IOC_MAGIC, 3)
+/* QRC boot from flash */
+#define QRC_BOOT_TO_FLASH _IO(QRC_IOC_MAGIC, 4)
+/* QRC get read buffer size */
+#define QRC_FIONREAD _IO(QRC_IOC_MAGIC, 5)
+
+enum qrcdev_state_t {
+ __STATE_IDLE,
+ __STATE_READING,
+ __STATE_WRITING,
+};
+
+enum qrc_interface {
+ UART = 0,
+ SPI,
+};
+
+enum qrcdev_tx {
+ __QRCDEV_TX_MIN = INT_MIN, /* make sure enum is signed (-1)*/
+ QRCDEV_TX_OK = 0x00, /* driver took care of packet */
+ QRCDEV_TX_BUSY = 0x10, /* driver tx path was busy*/
+};
+
+struct qrc_device_stats {
+ unsigned long rx_bytes;
+ unsigned long tx_bytes;
+ unsigned long rx_errors;
+ unsigned long tx_errors;
+ unsigned long collisions;
+ unsigned long rx_length_errors;
+ unsigned long rx_over_errors;
+ unsigned long rx_fifo_errors;
+};
+
+struct qrc_device_ops {
+ int (*qrcops_init)(struct qrc_dev *dev);
+ void (*qrcops_uninit)(struct qrc_dev *dev);
+ int (*qrcops_open)(struct qrc_dev *dev);
+ int (*qrcops_close)(struct qrc_dev *dev);
+ int (*qrcops_setup)(struct qrc_dev *dev);
+ enum qrcdev_tx (*qrcops_xmit)(const char __user *buf,
+ size_t data_length, struct qrc_dev *dev);
+ int (*qrcops_receive)(struct qrc_dev *dev,
+ char __user *buf, size_t count);
+ int (*qrcops_data_status)
+ (struct qrc_dev *dev);
+ int (*qrcops_config)(struct qrc_dev *dev);
+ void (*qrcops_data_clean)(struct qrc_dev *dev);
+};
+
+/* qrc char device */
+struct qrc_dev {
+ struct qrc_device_stats stats;
+ struct qrc_device_ops *qrc_ops; /* qrc dev ops */
+ struct mutex mutex; /* protect kfifo access */
+ wait_queue_head_t r_wait;
+ wait_queue_head_t w_wait;
+ struct fasync_struct *async_queue;
+ struct cdev cdev;
+ struct device *dev;
+ void *data;
+ int qrc_boot0_gpio;
+ int qrc_reset_gpio;
+};
+
+/**
+ * struct qrcuart - The qrcuart device structure.
+ * @qrc_dev: This is robotic controller device structure.
+ * It include interface for qrcuart.
+ * @lock: spinlock for transmitting lock.
+ * @tx_work: Flushes transmit TX buffer.
+ * @serdev: Serial device bus structure.
+ * @qrc_rx_fifo: Qrcuart receive buffer.
+ * @tx_head: String head in XMIT queue.
+ * @tx_left: Bytes left in XMIT queue.
+ * @tx_buffer: XMIT buffer.
+ * @is_open: Flag shows if the device is open.
+ * This structure is used to define robotic controller uart device.
+ */
+struct qrcuart {
+ struct qrc_dev *qrc_dev;
+ spinlock_t lock; /* spinlock for transmitting lock */
+ struct work_struct tx_work;
+ struct serdev_device *serdev;
+ struct kfifo qrc_rx_fifo;
+ unsigned char *tx_head;
+ int tx_left;
+ unsigned char *tx_buffer;
+ bool is_open;
+};
+
+struct qrcspi {
+ struct qrc_dev *qrc_dev;
+ spinlock_t lock; /* transmit lock */
+};
+
+static inline void qrc_set_data(struct qrc_dev *dev, void *data)
+{
+ dev->data = data;
+}
+
+static inline void *qrc_get_data(const struct qrc_dev *dev)
+{
+ return dev->data;
+}
+
+int qrc_register_device(struct qrc_dev *qdev, struct device *dev);
+void qrc_unregister(struct qrc_dev *qdev);
+
+#endif
+
diff --git a/drivers/misc/qrc/qrc_uart.c b/drivers/misc/qrc/qrc_uart.c
new file mode 100644
index 000000000000..74143d88c967
--- /dev/null
+++ b/drivers/misc/qrc/qrc_uart.c
@@ -0,0 +1,345 @@
+// SPDX-License-Identifier: GPL-2.0-only
+/* driver/misc/qrc/qrc_uart.c
+ *
+ * Copyright (c) 2022-2023 Qualcomm Innovation Center, Inc. All rights reserved.
+ */
+
+#include <linux/errno.h>
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/serdev.h>
+#include <linux/init.h>
+#include <linux/of.h>
+#include "qrc_core.h"
+
+#define QRC_RX_FIFO_SIZE 0x400
+#define QRC_TX_BUFF_SIZE 0x400
+#define QRCUART_DRV_NAME "qrcuart"
+#define QRC_DRV_VERSION "0.1.0"
+
+static int qrcuart_setup(struct qrc_dev *dev);
+
+static int
+qrc_uart_receive(struct serdev_device *serdev, const unsigned char *data,
+ size_t count)
+{
+ struct qrcuart *qrc = serdev_device_get_drvdata(serdev);
+ struct qrc_dev *qrc_dev = qrc->qrc_dev;
+ int ret;
+
+ /* check count */
+ ret = kfifo_avail(&qrc->qrc_rx_fifo);
+ if (!ret)
+ return 0;
+
+ if (count > ret)
+ count = ret;
+
+ ret = kfifo_in(&qrc->qrc_rx_fifo, data, count);
+ if (!ret)
+ return 0;
+
+ wake_up_interruptible(&qrc_dev->r_wait);
+
+ return count;
+}
+
+/* Write out any remaining transmit buffer. Scheduled when tty is writable */
+static void qrcuart_transmit(struct work_struct *work)
+{
+ struct qrcuart *qrc = container_of(work, struct qrcuart, tx_work);
+ int written;
+
+ spin_lock_bh(&qrc->lock);
+
+ if (qrc->tx_left <= 0) {
+ /* Now serial buffer is almost free & we can start
+ * transmission of another packet
+ */
+ spin_unlock_bh(&qrc->lock);
+ return;
+ }
+
+ written = serdev_device_write_buf(qrc->serdev, qrc->tx_head,
+ qrc->tx_left);
+ if (written > 0) {
+ qrc->tx_left -= written;
+ qrc->tx_head += written;
+ }
+ spin_unlock_bh(&qrc->lock);
+}
+
+/* Called by the driver when there's room for more data.
+ * Schedule the transmit.
+ */
+static void qrc_uart_wakeup(struct serdev_device *serdev)
+{
+ struct qrcuart *qrc = serdev_device_get_drvdata(serdev);
+
+ schedule_work(&qrc->tx_work);
+}
+
+static struct serdev_device_ops qrc_serdev_ops = {
+ .receive_buf = qrc_uart_receive,
+ .write_wakeup = qrc_uart_wakeup,
+};
+
+/*----------------Interface to QRC core -----------------------------*/
+
+static int qrcuart_open(struct qrc_dev *dev)
+{
+ struct qrcuart *qrc = qrc_get_data(dev);
+ struct serdev_device *serdev = qrc->serdev;
+ int ret;
+
+ if (!qrc->is_open) {
+ ret = serdev_device_open(serdev);
+ if (ret) {
+ dev_err(dev->dev, "qrcuart :Unable to open device\n");
+ return ret;
+ }
+ serdev_device_set_baudrate(serdev, 115200);
+ serdev_device_set_flow_control(serdev, false);
+ qrc->is_open = true;
+ }
+
+ return 0;
+}
+
+static int qrcuart_close(struct qrc_dev *dev)
+{
+ struct qrcuart *qrc = qrc_get_data(dev);
+ struct serdev_device *serdev = qrc->serdev;
+
+ flush_work(&qrc->tx_work);
+ spin_lock_bh(&qrc->lock);
+ qrc->tx_left = 0;
+ spin_unlock_bh(&qrc->lock);
+
+ if (qrc->is_open) {
+ serdev_device_close(serdev);
+ qrc->is_open = false;
+ }
+
+ return 0;
+}
+
+static int qrcuart_init(struct qrc_dev *dev)
+{
+ struct qrcuart *qrc = qrc_get_data(dev);
+ size_t len;
+ int ret;
+
+ /* Finish setting up the device info. */
+ len = QRC_TX_BUFF_SIZE;
+ qrc->tx_buffer = devm_kmalloc(&qrc->serdev->dev, len, GFP_KERNEL);
+
+ if (!qrc->tx_buffer)
+ return -ENOMEM;
+
+ qrc->tx_head = qrc->tx_buffer;
+ qrc->tx_left = 0;
+
+ ret = kfifo_alloc(&qrc->qrc_rx_fifo, QRC_RX_FIFO_SIZE,
+ GFP_KERNEL);
+ if (ret)
+ return -ENOMEM;
+
+ return 0;
+}
+
+static void qrcuart_uninit(struct qrc_dev *dev)
+{
+ struct qrcuart *qrc = qrc_get_data(dev);
+
+ kfifo_free(&qrc->qrc_rx_fifo);
+}
+
+/*put data from kfifo to qrc fifo */
+static int qrcuart_receive(struct qrc_dev *dev, char __user *buf,
+ size_t count)
+{
+ struct qrcuart *qrc = qrc_get_data(dev);
+ u32 fifo_len, trans_len;
+
+ if (!kfifo_is_empty(&qrc->qrc_rx_fifo)) {
+ fifo_len = kfifo_len(&qrc->qrc_rx_fifo);
+ if (count > fifo_len)
+ count = fifo_len;
+ if (kfifo_to_user(&qrc->qrc_rx_fifo,
+ (void *)buf, count, &trans_len))
+ return -EFAULT;
+ return trans_len;
+ }
+ return 0;
+}
+
+static int qrcuart_data_status(struct qrc_dev *dev)
+{
+ struct qrcuart *qrc = qrc_get_data(dev);
+
+ return kfifo_len(&qrc->qrc_rx_fifo);
+}
+
+static void qrcuart_data_clean(struct qrc_dev *dev)
+{
+ struct qrcuart *qrc = qrc_get_data(dev);
+
+ kfifo_reset(&qrc->qrc_rx_fifo);
+}
+
+static enum qrcdev_tx qrcuart_xmit(const char __user *buf,
+ size_t data_length, struct qrc_dev *dev)
+{
+ struct qrcuart *qrc = qrc_get_data(dev);
+ struct qrc_device_stats *n_stats = &dev->stats;
+ size_t written;
+ u8 *pos;
+
+ WARN_ON(qrc->tx_left);
+
+ pos = qrc->tx_buffer + qrc->tx_left;
+ if ((data_length + qrc->tx_left) > QRC_TX_BUFF_SIZE) {
+ dev_err(dev->dev, "qrcuart transmit date overflow %ld\n", data_length);
+ return __QRCDEV_TX_MIN;
+ }
+
+ if (copy_from_user(pos, buf, data_length))
+ return __QRCDEV_TX_MIN;
+
+ pos += data_length;
+
+ spin_lock(&qrc->lock);
+
+ written = serdev_device_write_buf(qrc->serdev, qrc->tx_buffer,
+ pos - qrc->tx_buffer);
+ if (written > 0) {
+ qrc->tx_left = (pos - qrc->tx_buffer) - written;
+ qrc->tx_head = qrc->tx_buffer + written;
+ n_stats->tx_bytes += written;
+ }
+
+ spin_unlock(&qrc->lock);
+
+ return QRCDEV_TX_OK;
+}
+
+static int qrcuart_config(struct qrc_dev *dev)
+{
+ /*baudrate,wordlength ... config*/
+ return 0;
+}
+
+static struct qrc_device_ops qrcuart_qrc_ops = {
+ .qrcops_open = qrcuart_open,
+ .qrcops_close = qrcuart_close,
+ .qrcops_init = qrcuart_init,
+ .qrcops_uninit = qrcuart_uninit,
+ .qrcops_xmit = qrcuart_xmit,
+ .qrcops_receive = qrcuart_receive,
+ .qrcops_config = qrcuart_config,
+ .qrcops_setup = qrcuart_setup,
+ .qrcops_data_status = qrcuart_data_status,
+ .qrcops_data_clean = qrcuart_data_clean,
+};
+
+static int qrcuart_setup(struct qrc_dev *dev)
+{
+ dev->qrc_ops = &qrcuart_qrc_ops;
+ return 0;
+}
+
+static int qrc_uart_probe(struct serdev_device *serdev)
+{
+ struct qrc_dev *qdev;
+ struct qrcuart *qrc;
+ int ret = 0;
+
+ qrc = kmalloc(sizeof(*qrc), GFP_KERNEL);
+ if (!qrc)
+ return -ENOMEM;
+ qdev = kmalloc(sizeof(*qdev), GFP_KERNEL);
+ if (!qdev) {
+ kfree(qrc);
+ return -ENOMEM;
+ }
+ qdev->dev = &serdev->dev;
+ qrc_set_data(qdev, qrc);
+
+ qrc->qrc_dev = qdev;
+ qrc->serdev = serdev;
+ spin_lock_init(&qrc->lock);
+ INIT_WORK(&qrc->tx_work, qrcuart_transmit);
+ qrcuart_setup(qdev);
+ ret = qrcuart_init(qdev);
+ if (ret) {
+ dev_err(qdev->dev, "qrcuart: Fail to init qrc structure\n");
+ kfree(qdev);
+ kfree(qrc);
+ return ret;
+ }
+ serdev_device_set_drvdata(serdev, qrc);
+ serdev_device_set_client_ops(serdev, &qrc_serdev_ops);
+
+ ret = serdev_device_open(serdev);
+ if (ret) {
+ dev_err(qdev->dev, "qrcuart :Unable to open device\n");
+ goto free;
+ }
+ serdev_device_close(serdev);
+ qrc->is_open = false;
+
+ ret = qrc_register_device(qdev, &serdev->dev);
+
+ if (ret) {
+ dev_err(qdev->dev, "qrcuart: Unable to register qrc device\n");
+ cancel_work_sync(&qrc->tx_work);
+ goto free;
+ }
+
+ return 0;
+
+free:
+ qrcuart_uninit(qdev);
+ kfree(qdev);
+ kfree(qrc);
+ return ret;
+}
+
+static void qrc_uart_remove(struct serdev_device *serdev)
+{
+ struct qrcuart *qrc = serdev_device_get_drvdata(serdev);
+
+ if (qrc->is_open)
+ serdev_device_close(serdev);
+
+ qrcuart_uninit(qrc->qrc_dev);
+ cancel_work_sync(&qrc->tx_work);
+ qrc_unregister(qrc->qrc_dev);
+ kfree(qrc->qrc_dev);
+ kfree(qrc);
+ dev_info(&serdev->dev, "qrcuart drv removed\n");
+}
+
+static const struct of_device_id qrc_uart_of_match[] = {
+ { .compatible = "qcom,qrc-uart", },
+ {}
+};
+
+MODULE_DEVICE_TABLE(of, qrc_uart_of_match);
+
+static struct serdev_device_driver qrc_uart_driver = {
+ .probe = qrc_uart_probe,
+ .remove = qrc_uart_remove,
+ .driver = {
+ .name = QRCUART_DRV_NAME,
+ .of_match_table = of_match_ptr(qrc_uart_of_match),
+ },
+};
+
+module_serdev_device_driver(qrc_uart_driver);
+
+/**********************************************/
+
+MODULE_DESCRIPTION("Qualcomm Technologies, Inc. QRC Uart Driver");
+MODULE_LICENSE("GPL");
--
2.25.1
On Mon, Mar 04, 2024 at 12:53:16AM +0800, Canfeng Zhuang wrote:
> QRC Driver support functions:
What is "QRC"?
> - Read data from serial device port.
> - Write data to serial device port.
Shouldn't you be doing that in userspace? Why is this a kernel driver?
> - Pin control reset robotic controller.
>
> Signed-off-by: Canfeng Zhuang <[email protected]>
> ---
> drivers/misc/Kconfig | 1 +
> drivers/misc/Makefile | 1 +
> drivers/misc/qrc/Kconfig | 16 ++
> drivers/misc/qrc/Makefile | 6 +
> drivers/misc/qrc/qrc_core.c | 336 ++++++++++++++++++++++++++++++++++++++++++
> drivers/misc/qrc/qrc_core.h | 143 ++++++++++++++++++
Why do you have a .h file for a single driver?
> drivers/misc/qrc/qrc_uart.c | 345 ++++++++++++++++++++++++++++++++++++++++++++
> 7 files changed, 848 insertions(+)
>
> diff --git a/drivers/misc/Kconfig b/drivers/misc/Kconfig
> index 4fb291f0bf7c..a43108af6fde 100644
> --- a/drivers/misc/Kconfig
> +++ b/drivers/misc/Kconfig
> @@ -591,4 +591,5 @@ source "drivers/misc/cardreader/Kconfig"
> source "drivers/misc/uacce/Kconfig"
> source "drivers/misc/pvpanic/Kconfig"
> source "drivers/misc/mchp_pci1xxxx/Kconfig"
> +source "drivers/misc/qrc/Kconfig"
> endmenu
> diff --git a/drivers/misc/Makefile b/drivers/misc/Makefile
> index ea6ea5bbbc9c..ab3b2c4d99fa 100644
> --- a/drivers/misc/Makefile
> +++ b/drivers/misc/Makefile
> @@ -68,3 +68,4 @@ obj-$(CONFIG_TMR_INJECT) += xilinx_tmr_inject.o
> obj-$(CONFIG_TPS6594_ESM) += tps6594-esm.o
> obj-$(CONFIG_TPS6594_PFSM) += tps6594-pfsm.o
> obj-$(CONFIG_NSM) += nsm.o
> +obj-$(CONFIG_QCOM_QRC) += qrc/
> diff --git a/drivers/misc/qrc/Kconfig b/drivers/misc/qrc/Kconfig
> new file mode 100644
> index 000000000000..994985d7c320
> --- /dev/null
> +++ b/drivers/misc/qrc/Kconfig
> @@ -0,0 +1,16 @@
> +# SPDX-License-Identifier: GPL-2.0-only
> +#
> +# QRC device driver configuration
> +#
> +
> +menu "QCOM QRC device driver"
> +
> +config QCOM_QRC
> + tristate "QCOM QRC device driver for Robotic SDK MCU"
What is "QCOM", "QRC", SDK", and "MCU"?
> + help
> + This kernel configuration is used to enable robotic controller
> + device driver. Say M here if you want to enable robotic
> + controller device driver.
Please write more here, this doesn't really describe what is happening.
> + When in doubt, say N.
> +
> +endmenu
> diff --git a/drivers/misc/qrc/Makefile b/drivers/misc/qrc/Makefile
> new file mode 100644
> index 000000000000..da2cf81f3c59
> --- /dev/null
> +++ b/drivers/misc/qrc/Makefile
> @@ -0,0 +1,6 @@
> +# SPDX-License-Identifier: GPL-2.0-only
> +#
> +# Makefile for the QRC bus specific drivers.
> +
> +
> +obj-$(CONFIG_QCOM_QRC) += qrc_core.o qrc_uart.o
Why is a single driver 2 different files?
> diff --git a/drivers/misc/qrc/qrc_core.c b/drivers/misc/qrc/qrc_core.c
> new file mode 100644
> index 000000000000..5cedb050dac4
> --- /dev/null
> +++ b/drivers/misc/qrc/qrc_core.c
> @@ -0,0 +1,336 @@
> +// SPDX-License-Identifier: GPL-2.0-only
> +/* driver/misc/qrc/qrc_core.c
Why is the filename here?
> + *
> + * Copyright (c) 2022-2023 Qualcomm Innovation Center, Inc. All rights reserved.
> + */
> +
> +#include <linux/module.h>
> +#include <linux/types.h>
> +#include <linux/sched.h>
> +#include <linux/init.h>
> +#include <linux/cdev.h>
> +#include <linux/slab.h>
> +#include <linux/poll.h>
> +#include <linux/platform_device.h>
> +#include <linux/of_device.h>
> +#include <linux/of.h>
> +#include <linux/of_gpio.h>
> +#include <linux/gpio.h>
> +#include <linux/delay.h>
> +
> +#include "qrc_core.h"
> +
> +#define QRC_DEVICE_NAME "qrc"
KBUILD_MODNAME.
> +static dev_t qrc_devt;
> +static struct class *qrc_class;
Please use class_register(), not class_create().
I've stopped here, please get someone in your group to review this
before sending it out again, you have internal experience with kernel
drivers, please take advantage of it.
thanks,
greg k-h
On 03/03/2024 17:53, Canfeng Zhuang wrote:
> Merge Qualcomm-specific qrc binding
Merge? No, instead describe the hardware.
Similar problem with the sibject.
>
> Signed-off-by: Canfeng Zhuang <[email protected]>
> ---
> .../devicetree/bindings/misc/qcom,qrc.yaml | 32 ++++++++++++++++++++++
> 1 file changed, 32 insertions(+)
>
> diff --git a/Documentation/devicetree/bindings/misc/qcom,qrc.yaml b/Documentation/devicetree/bindings/misc/qcom,qrc.yaml
> new file mode 100644
> index 000000000000..730efd679ba0
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/misc/qcom,qrc.yaml
> @@ -0,0 +1,32 @@
> +# SPDX-License-Identifier: (GPL-2.0-only OR BSD-2-Clause)
> +%YAML 1.2
> +---
> +$id: http://devicetree.org/schemas/misc/qcom,qrc.yaml#
> +$schema: http://devicetree.org/meta-schemas/core.yaml#
> +
> +title: Qualcomm Robotics Communication Driver
Driver? Unfortunately bindings are for hardware, not drivers.
> +
> +maintainers:
> + - Srinivas Kandagatla <[email protected]>
> +
> +description: |
Do not need '|' unless you need to preserve formatting.
> + The QRC (Qualcomm Robotics Communication) driver is used for information interaction
Agaim, driver?
> + between the robot control board and the main board when using a uart port connection.
> + This Driver will support uart read & write and robot control board
No, describe the hardware.
> + reset function.
> +
> +properties:
> + compatible:
> + const: qcom,qrc-uart
> +
> +required:
> + - compatible
> +
> +additionalProperties: false
> +
> +examples:
> + - |
> + qrc: qcom,qrc_uart {
How does it remotely look like upstream DTS? Please don't send
downstream/vendor DTS before cleaning it up. Before posting, please read
submitting patches and/or quite extensive Qualcomm upstreaming guides.
> + compatible = "qcom,qrc-uart";
Nope, so this is just to instantiate Linux device? No resources? This
looks really incomplete.
> + };
> +
>
Best regards,
Krzysztof
On 03/03/2024 17:53, Canfeng Zhuang wrote:
> QRC Driver support functions:
> - Read data from serial device port.
> - Write data to serial device port.
> - Pin control reset robotic controller.
>
> Signed-off-by: Canfeng Zhuang <[email protected]>
> ---
> drivers/misc/Kconfig | 1 +
> drivers/misc/Makefile | 1 +
> drivers/misc/qrc/Kconfig | 16 ++
> drivers/misc/qrc/Makefile | 6 +
> drivers/misc/qrc/qrc_core.c | 336 ++++++++++++++++++++++++++++++++++++++++++
> drivers/misc/qrc/qrc_core.h | 143 ++++++++++++++++++
> drivers/misc/qrc/qrc_uart.c | 345 ++++++++++++++++++++++++++++++++++++++++++++
> 7 files changed, 848 insertions(+)
>
> diff --git a/drivers/misc/Kconfig b/drivers/misc/Kconfig
> index 4fb291f0bf7c..a43108af6fde 100644
> --- a/drivers/misc/Kconfig
> +++ b/drivers/misc/Kconfig
> @@ -591,4 +591,5 @@ source "drivers/misc/cardreader/Kconfig"
> source "drivers/misc/uacce/Kconfig"
> source "drivers/misc/pvpanic/Kconfig"
> source "drivers/misc/mchp_pci1xxxx/Kconfig"
> +source "drivers/misc/qrc/Kconfig"
> endmenu
> diff --git a/drivers/misc/Makefile b/drivers/misc/Makefile
> index ea6ea5bbbc9c..ab3b2c4d99fa 100644
> --- a/drivers/misc/Makefile
> +++ b/drivers/misc/Makefile
> @@ -68,3 +68,4 @@ obj-$(CONFIG_TMR_INJECT) += xilinx_tmr_inject.o
> obj-$(CONFIG_TPS6594_ESM) += tps6594-esm.o
> obj-$(CONFIG_TPS6594_PFSM) += tps6594-pfsm.o
> obj-$(CONFIG_NSM) += nsm.o
> +obj-$(CONFIG_QCOM_QRC) += qrc/
> diff --git a/drivers/misc/qrc/Kconfig b/drivers/misc/qrc/Kconfig
> new file mode 100644
> index 000000000000..994985d7c320
> --- /dev/null
> +++ b/drivers/misc/qrc/Kconfig
> @@ -0,0 +1,16 @@
> +# SPDX-License-Identifier: GPL-2.0-only
> +#
> +# QRC device driver configuration
> +#
> +
> +menu "QCOM QRC device driver"
> +
> +config QCOM_QRC
> + tristate "QCOM QRC device driver for Robotic SDK MCU"
> + help
> + This kernel configuration is used to enable robotic controller
> + device driver. Say M here if you want to enable robotic
> + controller device driver.
> + When in doubt, say N.
> +
> +endmenu
> diff --git a/drivers/misc/qrc/Makefile b/drivers/misc/qrc/Makefile
> new file mode 100644
> index 000000000000..da2cf81f3c59
> --- /dev/null
> +++ b/drivers/misc/qrc/Makefile
> @@ -0,0 +1,6 @@
> +# SPDX-License-Identifier: GPL-2.0-only
> +#
> +# Makefile for the QRC bus specific drivers.
QRC bus? Nothing anywhere suggested this is a bus.
Limited review because this really looks like some vendor code, not
cleaned for upstream submission.
> +
> +
> +obj-$(CONFIG_QCOM_QRC) += qrc_core.o qrc_uart.o
..
> +
> +static int qrcuart_config(struct qrc_dev *dev)
> +{
> + /*baudrate,wordlength ... config*/
> + return 0;
> +}
> +
> +static struct qrc_device_ops qrcuart_qrc_ops = {
What is this and why do you need it? Don't define your ops without need.
Just call functions directly.
> + .qrcops_open = qrcuart_open,
> + .qrcops_close = qrcuart_close,
> + .qrcops_init = qrcuart_init,
> + .qrcops_uninit = qrcuart_uninit,
> + .qrcops_xmit = qrcuart_xmit,
> + .qrcops_receive = qrcuart_receive,
> + .qrcops_config = qrcuart_config,
> + .qrcops_setup = qrcuart_setup,
> + .qrcops_data_status = qrcuart_data_status,
> + .qrcops_data_clean = qrcuart_data_clean,
> +};
> +
> +static int qrcuart_setup(struct qrc_dev *dev)
> +{
> + dev->qrc_ops = &qrcuart_qrc_ops;
> + return 0;
> +}
> +
> +static int qrc_uart_probe(struct serdev_device *serdev)
> +{
> + struct qrc_dev *qdev;
> + struct qrcuart *qrc;
> + int ret = 0;
> +
> + qrc = kmalloc(sizeof(*qrc), GFP_KERNEL);
> + if (!qrc)
> + return -ENOMEM;
> + qdev = kmalloc(sizeof(*qdev), GFP_KERNEL);
Just use devm*. What is this code? Ancient vendor, 20 year old stuff?
> + if (!qdev) {
> + kfree(qrc);
> + return -ENOMEM;
> + }
> + qdev->dev = &serdev->dev;
> + qrc_set_data(qdev, qrc);
> +
> + qrc->qrc_dev = qdev;
> + qrc->serdev = serdev;
> + spin_lock_init(&qrc->lock);
> + INIT_WORK(&qrc->tx_work, qrcuart_transmit);
> + qrcuart_setup(qdev);
> + ret = qrcuart_init(qdev);
> + if (ret) {
> + dev_err(qdev->dev, "qrcuart: Fail to init qrc structure\n");
> + kfree(qdev);
> + kfree(qrc);
> + return ret;
> + }
> + serdev_device_set_drvdata(serdev, qrc);
> + serdev_device_set_client_ops(serdev, &qrc_serdev_ops);
> +
> + ret = serdev_device_open(serdev);
> + if (ret) {
> + dev_err(qdev->dev, "qrcuart :Unable to open device\n");
Whitespace typos.
> + goto free;
> + }
> + serdev_device_close(serdev);
> + qrc->is_open = false;
> +
> + ret = qrc_register_device(qdev, &serdev->dev);
> +
> + if (ret) {
> + dev_err(qdev->dev, "qrcuart: Unable to register qrc device\n");
> + cancel_work_sync(&qrc->tx_work);
> + goto free;
> + }
> +
> + return 0;
> +
> +free:
free or uninint? Your error handling is messy.
> + qrcuart_uninit(qdev);
> + kfree(qdev);
> + kfree(qrc);
> + return ret;
> +}
> +
> +static void qrc_uart_remove(struct serdev_device *serdev)
> +{
> + struct qrcuart *qrc = serdev_device_get_drvdata(serdev);
> +
> + if (qrc->is_open)
> + serdev_device_close(serdev);
> +
> + qrcuart_uninit(qrc->qrc_dev);
> + cancel_work_sync(&qrc->tx_work);
> + qrc_unregister(qrc->qrc_dev);
> + kfree(qrc->qrc_dev);
> + kfree(qrc);
> + dev_info(&serdev->dev, "qrcuart drv removed\n");
Drop such simple function entry/exit messages. Not needed and not helpful.
> +}
> +
> +static const struct of_device_id qrc_uart_of_match[] = {
> + { .compatible = "qcom,qrc-uart", },
> + {}
> +};
> +
> +MODULE_DEVICE_TABLE(of, qrc_uart_of_match);
> +
> +static struct serdev_device_driver qrc_uart_driver = {
> + .probe = qrc_uart_probe,
> + .remove = qrc_uart_remove,
> + .driver = {
> + .name = QRCUART_DRV_NAME,
> + .of_match_table = of_match_ptr(qrc_uart_of_match),
Drop of_match_ptr. You have warnings here.
> + },
> +};
> +
> +module_serdev_device_driver(qrc_uart_driver);
> +
> +/**********************************************/
Drop
> +
> +MODULE_DESCRIPTION("Qualcomm Technologies, Inc. QRC Uart Driver");
> +MODULE_LICENSE("GPL");
>
Best regards,
Krzysztof
Hi Canfeng,
kernel test robot noticed the following build warnings:
[auto build test WARNING on 805d849d7c3cc1f38efefd48b2480d62b7b5dcb7]
url: https://github.com/intel-lab-lkp/linux/commits/Canfeng-Zhuang/misc-qualcomm-QRC-driver-for-Robotic-SDK-MCU/20240304-005601
base: 805d849d7c3cc1f38efefd48b2480d62b7b5dcb7
patch link: https://lore.kernel.org/r/20240304-qcom_qrc-v1-1-2a709f95fd61%40quicinc.com
patch subject: [PATCH 1/2] misc: qualcomm: QRC driver for Robotic SDK MCU
config: hexagon-allyesconfig (https://download.01.org/0day-ci/archive/20240304/[email protected]/config)
compiler: clang version 19.0.0git (https://github.com/llvm/llvm-project 325f51237252e6dab8e4e1ea1fa7acbb4faee1cd)
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20240304/[email protected]/reproduce)
If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <[email protected]>
| Closes: https://lore.kernel.org/oe-kbuild-all/[email protected]/
All warnings (new ones prefixed by >>):
In file included from drivers/misc/qrc/qrc_uart.c:10:
In file included from include/linux/serdev.h:10:
In file included from include/linux/iopoll.h:14:
In file included from include/linux/io.h:13:
In file included from arch/hexagon/include/asm/io.h:328:
include/asm-generic/io.h:547:31: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
547 | val = __raw_readb(PCI_IOBASE + addr);
| ~~~~~~~~~~ ^
include/asm-generic/io.h:560:61: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
560 | val = __le16_to_cpu((__le16 __force)__raw_readw(PCI_IOBASE + addr));
| ~~~~~~~~~~ ^
include/uapi/linux/byteorder/little_endian.h:37:51: note: expanded from macro '__le16_to_cpu'
37 | #define __le16_to_cpu(x) ((__force __u16)(__le16)(x))
| ^
In file included from drivers/misc/qrc/qrc_uart.c:10:
In file included from include/linux/serdev.h:10:
In file included from include/linux/iopoll.h:14:
In file included from include/linux/io.h:13:
In file included from arch/hexagon/include/asm/io.h:328:
include/asm-generic/io.h:573:61: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
573 | val = __le32_to_cpu((__le32 __force)__raw_readl(PCI_IOBASE + addr));
| ~~~~~~~~~~ ^
include/uapi/linux/byteorder/little_endian.h:35:51: note: expanded from macro '__le32_to_cpu'
35 | #define __le32_to_cpu(x) ((__force __u32)(__le32)(x))
| ^
In file included from drivers/misc/qrc/qrc_uart.c:10:
In file included from include/linux/serdev.h:10:
In file included from include/linux/iopoll.h:14:
In file included from include/linux/io.h:13:
In file included from arch/hexagon/include/asm/io.h:328:
include/asm-generic/io.h:584:33: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
584 | __raw_writeb(value, PCI_IOBASE + addr);
| ~~~~~~~~~~ ^
include/asm-generic/io.h:594:59: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
594 | __raw_writew((u16 __force)cpu_to_le16(value), PCI_IOBASE + addr);
| ~~~~~~~~~~ ^
include/asm-generic/io.h:604:59: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
604 | __raw_writel((u32 __force)cpu_to_le32(value), PCI_IOBASE + addr);
| ~~~~~~~~~~ ^
In file included from drivers/misc/qrc/qrc_uart.c:13:
In file included from drivers/misc/qrc/qrc_core.h:14:
In file included from include/linux/kfifo.h:42:
In file included from include/linux/scatterlist.h:8:
In file included from include/linux/mm.h:2188:
include/linux/vmstat.h:522:36: warning: arithmetic between different enumeration types ('enum node_stat_item' and 'enum lru_list') [-Wenum-enum-conversion]
522 | return node_stat_name(NR_LRU_BASE + lru) + 3; // skip "nr_"
| ~~~~~~~~~~~ ^ ~~~
>> drivers/misc/qrc/qrc_uart.c:203:61: warning: format specifies type 'long' but the argument has type 'size_t' (aka 'unsigned int') [-Wformat]
203 | dev_err(dev->dev, "qrcuart transmit date overflow %ld\n", data_length);
| ~~~ ^~~~~~~~~~~
| %zu
include/linux/dev_printk.h:144:65: note: expanded from macro 'dev_err'
144 | dev_printk_index_wrap(_dev_err, KERN_ERR, dev, dev_fmt(fmt), ##__VA_ARGS__)
| ~~~ ^~~~~~~~~~~
include/linux/dev_printk.h:110:23: note: expanded from macro 'dev_printk_index_wrap'
110 | _p_func(dev, fmt, ##__VA_ARGS__); \
| ~~~ ^~~~~~~~~~~
8 warnings generated.
vim +203 drivers/misc/qrc/qrc_uart.c
> 13 #include "qrc_core.h"
14
15 #define QRC_RX_FIFO_SIZE 0x400
16 #define QRC_TX_BUFF_SIZE 0x400
17 #define QRCUART_DRV_NAME "qrcuart"
18 #define QRC_DRV_VERSION "0.1.0"
19
20 static int qrcuart_setup(struct qrc_dev *dev);
21
22 static int
23 qrc_uart_receive(struct serdev_device *serdev, const unsigned char *data,
24 size_t count)
25 {
26 struct qrcuart *qrc = serdev_device_get_drvdata(serdev);
27 struct qrc_dev *qrc_dev = qrc->qrc_dev;
28 int ret;
29
30 /* check count */
31 ret = kfifo_avail(&qrc->qrc_rx_fifo);
32 if (!ret)
33 return 0;
34
35 if (count > ret)
36 count = ret;
37
38 ret = kfifo_in(&qrc->qrc_rx_fifo, data, count);
39 if (!ret)
40 return 0;
41
42 wake_up_interruptible(&qrc_dev->r_wait);
43
44 return count;
45 }
46
47 /* Write out any remaining transmit buffer. Scheduled when tty is writable */
48 static void qrcuart_transmit(struct work_struct *work)
49 {
50 struct qrcuart *qrc = container_of(work, struct qrcuart, tx_work);
51 int written;
52
53 spin_lock_bh(&qrc->lock);
54
55 if (qrc->tx_left <= 0) {
56 /* Now serial buffer is almost free & we can start
57 * transmission of another packet
58 */
59 spin_unlock_bh(&qrc->lock);
60 return;
61 }
62
63 written = serdev_device_write_buf(qrc->serdev, qrc->tx_head,
64 qrc->tx_left);
65 if (written > 0) {
66 qrc->tx_left -= written;
67 qrc->tx_head += written;
68 }
69 spin_unlock_bh(&qrc->lock);
70 }
71
72 /* Called by the driver when there's room for more data.
73 * Schedule the transmit.
74 */
75 static void qrc_uart_wakeup(struct serdev_device *serdev)
76 {
77 struct qrcuart *qrc = serdev_device_get_drvdata(serdev);
78
79 schedule_work(&qrc->tx_work);
80 }
81
82 static struct serdev_device_ops qrc_serdev_ops = {
83 .receive_buf = qrc_uart_receive,
84 .write_wakeup = qrc_uart_wakeup,
85 };
86
87 /*----------------Interface to QRC core -----------------------------*/
88
89 static int qrcuart_open(struct qrc_dev *dev)
90 {
91 struct qrcuart *qrc = qrc_get_data(dev);
92 struct serdev_device *serdev = qrc->serdev;
93 int ret;
94
95 if (!qrc->is_open) {
96 ret = serdev_device_open(serdev);
97 if (ret) {
98 dev_err(dev->dev, "qrcuart :Unable to open device\n");
99 return ret;
100 }
101 serdev_device_set_baudrate(serdev, 115200);
102 serdev_device_set_flow_control(serdev, false);
103 qrc->is_open = true;
104 }
105
106 return 0;
107 }
108
109 static int qrcuart_close(struct qrc_dev *dev)
110 {
111 struct qrcuart *qrc = qrc_get_data(dev);
112 struct serdev_device *serdev = qrc->serdev;
113
114 flush_work(&qrc->tx_work);
115 spin_lock_bh(&qrc->lock);
116 qrc->tx_left = 0;
117 spin_unlock_bh(&qrc->lock);
118
119 if (qrc->is_open) {
120 serdev_device_close(serdev);
121 qrc->is_open = false;
122 }
123
124 return 0;
125 }
126
127 static int qrcuart_init(struct qrc_dev *dev)
128 {
129 struct qrcuart *qrc = qrc_get_data(dev);
130 size_t len;
131 int ret;
132
133 /* Finish setting up the device info. */
134 len = QRC_TX_BUFF_SIZE;
135 qrc->tx_buffer = devm_kmalloc(&qrc->serdev->dev, len, GFP_KERNEL);
136
137 if (!qrc->tx_buffer)
138 return -ENOMEM;
139
140 qrc->tx_head = qrc->tx_buffer;
141 qrc->tx_left = 0;
142
143 ret = kfifo_alloc(&qrc->qrc_rx_fifo, QRC_RX_FIFO_SIZE,
144 GFP_KERNEL);
145 if (ret)
146 return -ENOMEM;
147
148 return 0;
149 }
150
151 static void qrcuart_uninit(struct qrc_dev *dev)
152 {
153 struct qrcuart *qrc = qrc_get_data(dev);
154
155 kfifo_free(&qrc->qrc_rx_fifo);
156 }
157
158 /*put data from kfifo to qrc fifo */
159 static int qrcuart_receive(struct qrc_dev *dev, char __user *buf,
160 size_t count)
161 {
162 struct qrcuart *qrc = qrc_get_data(dev);
163 u32 fifo_len, trans_len;
164
165 if (!kfifo_is_empty(&qrc->qrc_rx_fifo)) {
166 fifo_len = kfifo_len(&qrc->qrc_rx_fifo);
167 if (count > fifo_len)
168 count = fifo_len;
169 if (kfifo_to_user(&qrc->qrc_rx_fifo,
170 (void *)buf, count, &trans_len))
171 return -EFAULT;
172 return trans_len;
173 }
174 return 0;
175 }
176
177 static int qrcuart_data_status(struct qrc_dev *dev)
178 {
179 struct qrcuart *qrc = qrc_get_data(dev);
180
181 return kfifo_len(&qrc->qrc_rx_fifo);
182 }
183
184 static void qrcuart_data_clean(struct qrc_dev *dev)
185 {
186 struct qrcuart *qrc = qrc_get_data(dev);
187
188 kfifo_reset(&qrc->qrc_rx_fifo);
189 }
190
191 static enum qrcdev_tx qrcuart_xmit(const char __user *buf,
192 size_t data_length, struct qrc_dev *dev)
193 {
194 struct qrcuart *qrc = qrc_get_data(dev);
195 struct qrc_device_stats *n_stats = &dev->stats;
196 size_t written;
197 u8 *pos;
198
199 WARN_ON(qrc->tx_left);
200
201 pos = qrc->tx_buffer + qrc->tx_left;
202 if ((data_length + qrc->tx_left) > QRC_TX_BUFF_SIZE) {
> 203 dev_err(dev->dev, "qrcuart transmit date overflow %ld\n", data_length);
204 return __QRCDEV_TX_MIN;
205 }
206
207 if (copy_from_user(pos, buf, data_length))
208 return __QRCDEV_TX_MIN;
209
210 pos += data_length;
211
212 spin_lock(&qrc->lock);
213
214 written = serdev_device_write_buf(qrc->serdev, qrc->tx_buffer,
215 pos - qrc->tx_buffer);
216 if (written > 0) {
217 qrc->tx_left = (pos - qrc->tx_buffer) - written;
218 qrc->tx_head = qrc->tx_buffer + written;
219 n_stats->tx_bytes += written;
220 }
221
222 spin_unlock(&qrc->lock);
223
224 return QRCDEV_TX_OK;
225 }
226
--
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki
Hi Canfeng,
kernel test robot noticed the following build warnings:
[auto build test WARNING on 805d849d7c3cc1f38efefd48b2480d62b7b5dcb7]
url: https://github.com/intel-lab-lkp/linux/commits/Canfeng-Zhuang/misc-qualcomm-QRC-driver-for-Robotic-SDK-MCU/20240304-005601
base: 805d849d7c3cc1f38efefd48b2480d62b7b5dcb7
patch link: https://lore.kernel.org/r/20240304-qcom_qrc-v1-1-2a709f95fd61%40quicinc.com
patch subject: [PATCH 1/2] misc: qualcomm: QRC driver for Robotic SDK MCU
config: sh-allmodconfig (https://download.01.org/0day-ci/archive/20240304/[email protected]/config)
compiler: sh4-linux-gcc (GCC) 13.2.0
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20240304/[email protected]/reproduce)
If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <[email protected]>
| Closes: https://lore.kernel.org/oe-kbuild-all/[email protected]/
All warnings (new ones prefixed by >>):
In file included from include/linux/device.h:15,
from include/linux/serdev.h:9,
from drivers/misc/qrc/qrc_uart.c:10:
drivers/misc/qrc/qrc_uart.c: In function 'qrcuart_xmit':
>> drivers/misc/qrc/qrc_uart.c:203:35: warning: format '%ld' expects argument of type 'long int', but argument 3 has type 'size_t' {aka 'unsigned int'} [-Wformat=]
203 | dev_err(dev->dev, "qrcuart transmit date overflow %ld\n", data_length);
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
include/linux/dev_printk.h:110:30: note: in definition of macro 'dev_printk_index_wrap'
110 | _p_func(dev, fmt, ##__VA_ARGS__); \
| ^~~
include/linux/dev_printk.h:144:56: note: in expansion of macro 'dev_fmt'
144 | dev_printk_index_wrap(_dev_err, KERN_ERR, dev, dev_fmt(fmt), ##__VA_ARGS__)
| ^~~~~~~
drivers/misc/qrc/qrc_uart.c:203:17: note: in expansion of macro 'dev_err'
203 | dev_err(dev->dev, "qrcuart transmit date overflow %ld\n", data_length);
| ^~~~~~~
drivers/misc/qrc/qrc_uart.c:203:69: note: format string is defined here
203 | dev_err(dev->dev, "qrcuart transmit date overflow %ld\n", data_length);
| ~~^
| |
| long int
| %d
vim +203 drivers/misc/qrc/qrc_uart.c
190
191 static enum qrcdev_tx qrcuart_xmit(const char __user *buf,
192 size_t data_length, struct qrc_dev *dev)
193 {
194 struct qrcuart *qrc = qrc_get_data(dev);
195 struct qrc_device_stats *n_stats = &dev->stats;
196 size_t written;
197 u8 *pos;
198
199 WARN_ON(qrc->tx_left);
200
201 pos = qrc->tx_buffer + qrc->tx_left;
202 if ((data_length + qrc->tx_left) > QRC_TX_BUFF_SIZE) {
> 203 dev_err(dev->dev, "qrcuart transmit date overflow %ld\n", data_length);
204 return __QRCDEV_TX_MIN;
205 }
206
207 if (copy_from_user(pos, buf, data_length))
208 return __QRCDEV_TX_MIN;
209
210 pos += data_length;
211
212 spin_lock(&qrc->lock);
213
214 written = serdev_device_write_buf(qrc->serdev, qrc->tx_buffer,
215 pos - qrc->tx_buffer);
216 if (written > 0) {
217 qrc->tx_left = (pos - qrc->tx_buffer) - written;
218 qrc->tx_head = qrc->tx_buffer + written;
219 n_stats->tx_bytes += written;
220 }
221
222 spin_unlock(&qrc->lock);
223
224 return QRCDEV_TX_OK;
225 }
226
--
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki
Hi Canfeng,
kernel test robot noticed the following build errors:
[auto build test ERROR on 805d849d7c3cc1f38efefd48b2480d62b7b5dcb7]
url: https://github.com/intel-lab-lkp/linux/commits/Canfeng-Zhuang/misc-qualcomm-QRC-driver-for-Robotic-SDK-MCU/20240304-005601
base: 805d849d7c3cc1f38efefd48b2480d62b7b5dcb7
patch link: https://lore.kernel.org/r/20240304-qcom_qrc-v1-1-2a709f95fd61%40quicinc.com
patch subject: [PATCH 1/2] misc: qualcomm: QRC driver for Robotic SDK MCU
config: s390-allyesconfig (https://download.01.org/0day-ci/archive/20240304/[email protected]/config)
compiler: s390-linux-gcc (GCC) 13.2.0
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20240304/[email protected]/reproduce)
If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <[email protected]>
| Closes: https://lore.kernel.org/oe-kbuild-all/[email protected]/
All errors (new ones prefixed by >>):
>> drivers/misc/qrc/qrc_uart.c:83:24: error: initialization of 'ssize_t (*)(struct serdev_device *, const u8 *, size_t)' {aka 'long int (*)(struct serdev_device *, const unsigned char *, long unsigned int)'} from incompatible pointer type 'int (*)(struct serdev_device *, const unsigned char *, size_t)' {aka 'int (*)(struct serdev_device *, const unsigned char *, long unsigned int)'} [-Werror=incompatible-pointer-types]
83 | .receive_buf = qrc_uart_receive,
| ^~~~~~~~~~~~~~~~
drivers/misc/qrc/qrc_uart.c:83:24: note: (near initialization for 'qrc_serdev_ops.receive_buf')
cc1: some warnings being treated as errors
vim +83 drivers/misc/qrc/qrc_uart.c
81
82 static struct serdev_device_ops qrc_serdev_ops = {
> 83 .receive_buf = qrc_uart_receive,
84 .write_wakeup = qrc_uart_wakeup,
85 };
86
--
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki
On Mon, Mar 04, 2024 at 12:53:15AM +0800, Canfeng Zhuang wrote:
> QCOM QRC device driver is used for Robotic SDK MCU
>
Please review go/upstream and have your patches reviewed on the internal
list before posting to the public mailing lists.
Thank you,
Bjorn
> [commit]misc: qualcomm: QRC driver for Robotic SDK MCU
> This commit is used to enable robotic controller device driver.
> QRC Driver support functions:
> - Read data from serial device port.
> - Write data to serial device port.
> - Pin control reset robotic controller.
>
> [commit]dt-bindings: misc: merge qcom,qrc
> This commit is used to support qcom qrc devicetree binding.
>
> Signed-off-by: Canfeng Zhuang <[email protected]>
> ---
> Canfeng Zhuang (2):
> misc: qualcomm: QRC driver for Robotic SDK MCU
> dt-bindings: misc: merge qcom,qrc
>
> .../devicetree/bindings/misc/qcom,qrc.yaml | 32 ++
> drivers/misc/Kconfig | 1 +
> drivers/misc/Makefile | 1 +
> drivers/misc/qrc/Kconfig | 16 +
> drivers/misc/qrc/Makefile | 6 +
> drivers/misc/qrc/qrc_core.c | 336 ++++++++++++++++++++
> drivers/misc/qrc/qrc_core.h | 143 +++++++++
> drivers/misc/qrc/qrc_uart.c | 345 +++++++++++++++++++++
> 8 files changed, 880 insertions(+)
> ---
> base-commit: 805d849d7c3cc1f38efefd48b2480d62b7b5dcb7
> change-id: 20240304-qcom_qrc-778c8fad8846
>
> Best regards,
> --
> Canfeng Zhuang <[email protected]>
>