最近在调试集群处理平台,模块上使用了支持IPMI的BMC控制芯片。该芯片与ZYNQ通过I2C总线相连,上面跑IPMB协议。ZYNQ作机箱管理,对所有BMC进行控制,而BMC再控制本模块的负载上下电。
2、问题描述
ZYNQ与BMC通过I2C总线进行数据传输,按照VITA46.11规范,要求机箱管理既能做I2C的master,也能做i2c slave(此时BMC做master),于是要求ZYNQ能进行I2C主从模式切换。ZYNQ PS端的I2C控制器作为master很容易,之前也通过I2C控制器配置1848交换芯片,不会的是如何让I2C控制器运行在slave模式。问了一下AVNET代理,发现他们也没搞过。在Xilinx论坛上面发帖,老外给了一个他们ZYNQ作为i2c从的测试例子(见链接),但帮助不大,唯一的帮助就是让我相信I2C控制器肯定支持slave模式。在xilinx wiki(链接)上面可以看到新发布的驱动版本已经支持了I2C slave mode。
3、解决思路
对i2c-cadence.c驱动进行了代码分析,发现CONFIG_I2C_SLAVE的宏定义随处可见,其中最重要的莫过于下面这个地方。
Cdns_reg_slave和cdns_unreg_slave这两个函数从字面意义来看明显是对寄存器配置成slave或unslave模式的意思。可惜在linux内核代码中完全没找到调用这两个函数的地方。
由此看来,需要手动添加这两个函数,可以在i2c-dev.c中修改ioctl部分的代码,如下图所示,把原来i2c_slave部分的代码修改为调用reg_slave。
在reg_slave中增加了对i2c控制器进行复位的操作
在set mode函数中,直接往i2c控制器写值,设置control寄存器、设置i2c地址(由于地址固定,这里写死为0x10)、启用收数中断。
当i2c控制器收到数之后,会调用上面函数,根据模式进入不同的中断处理函数。
完成这些操作后,编译得到内核,在应用中可以通过ioctl设置i2c的从模式了。
在i2c驱动的收数函数中增加了部分打印
程序执行打印如下。
4、拓展
实现了i2c从模式后,就可以进行主从模式切换了。切换需要使用unreg_slave,再次修改i2c-dev.c
在unreg_slave函数中设置了i2c的模式为主模式
需要注意的是,从模式切换到主模式时需要判断总线是否被占用,这里用一个函数加以判断
在应用中调用下面函数即可进行切换
5、总结
I2c算是比较简单的驱动,但是调试的过程中遇到一些问题靠软件是查不出来的,需要硬件抓信号,如果硬件有问题,软件再怎么努力也没用。所以以后遇到类似的情况,当软件再也查不出问题时,一定要让硬件查一查,否则必然是白白浪费时间。
6、相关代码
i2c-cadence.c
- /*
- * I2C bus driver for the Cadence I2C controller.
- *
- * Copyright (C) 2009 - 2014 Xilinx, Inc.
- *
- * This program is free software; you can redistribute it
- * and/or modify it under the terms of the GNU General Public
- * License as published by the Free Software Foundation;
- * either version 2 of the License, or (at your option) any
- * later version.
- */
-
- #include <linux/clk.h>
- #include <linux/delay.h>
- #include <linux/i2c.h>
- #include <linux/interrupt.h>
- #include <linux/io.h>
- #include <linux/module.h>
- #include <linux/platform_device.h>
- #include <linux/of.h>
- #include <linux/of_gpio.h>
- #include <linux/pm_runtime.h>
- #include <linux/pinctrl/consumer.h>
- #include <linux/ioctl.h>
-
- #include <linux/kernel.h>
- #include <linux/version.h>
- #include <linux/fs.h>
- #include <linux/cdev.h>
- #include <linux/device.h>
- #include <linux/errno.h>
- #include <asm/uaccess.h>
-
- #include "ring.h"
- //#include "query_ioctl.h"
-
- //DECLARE_RING(i2c_recv_ring, 256)
-
- ring_t i2c_recv_ring = { 0, 0, 256};
-
- //query_arg_t q;
-
- /* Register offsets for the I2C device. */
- #define CDNS_I2C_CR_OFFSET 0x00 /* Control Register, RW */
- #define CDNS_I2C_SR_OFFSET 0x04 /* Status Register, RO */
- #define CDNS_I2C_ADDR_OFFSET 0x08 /* I2C Address Register, RW */
- #define CDNS_I2C_DATA_OFFSET 0x0C /* I2C Data Register, RW */
- #define CDNS_I2C_ISR_OFFSET 0x10 /* IRQ Status Register, RW */
- #define CDNS_I2C_XFER_SIZE_OFFSET 0x14 /* Transfer Size Register, RW */
- #define CDNS_I2C_SLV_PAUSE_OFFSET 0x18 /* Transfer Size Register, RW */
- #define CDNS_I2C_TIME_OUT_OFFSET 0x1C /* Time Out Register, RW */
- #define CDNS_I2C_IMR_OFFSET 0x20 /* IRQ Mask Register, RO */
- #define CDNS_I2C_IER_OFFSET 0x24 /* IRQ Enable Register, WO */
- #define CDNS_I2C_IDR_OFFSET 0x28 /* IRQ Disable Register, WO */
-
- /* Control Register Bit mask definitions */
- #define CDNS_I2C_CR_SLVMON BIT(5) /* Slave monitor mode bit */
- #define CDNS_I2C_CR_HOLD BIT(4) /* Hold Bus bit */
- #define CDNS_I2C_CR_ACK_EN BIT(3)
- #define CDNS_I2C_CR_NEA BIT(2)
- #define CDNS_I2C_CR_MS BIT(1)
- /* Read or Write Master transfer 0 = Transmitter, 1 = Receiver */
- #define CDNS_I2C_CR_RW BIT(0)
- /* 1 = Auto init FIFO to zeroes */
- #define CDNS_I2C_CR_CLR_FIFO BIT(6)
- #define CDNS_I2C_CR_DIVA_SHIFT 14
- #define CDNS_I2C_CR_DIVA_MASK (3 << CDNS_I2C_CR_DIVA_SHIFT)
- #define CDNS_I2C_CR_DIVB_SHIFT 8
- #define CDNS_I2C_CR_DIVB_MASK (0x3f << CDNS_I2C_CR_DIVB_SHIFT)
-
- #define CDNS_I2C_CR_SLAVE_EN_MASK (CDNS_I2C_CR_CLR_FIFO | \
- CDNS_I2C_CR_NEA | \
- CDNS_I2C_CR_ACK_EN | \
- CDNS_I2C_CR_MS)
-
- /* Status Register Bit mask definitions */
- #define CDNS_I2C_SR_BA BIT(8)
- #define CDNS_I2C_SR_TXDV BIT(6)
- #define CDNS_I2C_SR_RXDV BIT(5)
- #define CDNS_I2C_SR_RXRW BIT(3)
-
- /*
- * I2C Address Register Bit mask definitions
- * Normal addressing mode uses [6:0] bits. Extended addressing mode uses [9:0]
- * bits. A write access to this register always initiates a transfer if the I2C
- * is in master mode.
- */
- #define CDNS_I2C_ADDR_MASK 0x000003FF /* I2C Address Mask */
-
- /*
- * I2C Interrupt Registers Bit mask definitions
- * All the four interrupt registers (Status/Mask/Enable/Disable) have the same
- * bit definitions.
- */
- #define CDNS_I2C_IXR_ARB_LOST BIT(9)
- #define CDNS_I2C_IXR_RX_UNF BIT(7)
- #define CDNS_I2C_IXR_TX_OVF BIT(6)
- #define CDNS_I2C_IXR_RX_OVF BIT(5)
- #define CDNS_I2C_IXR_SLV_RDY BIT(4)
- #define CDNS_I2C_IXR_TO BIT(3)
- #define CDNS_I2C_IXR_NACK BIT(2)
- #define CDNS_I2C_IXR_DATA BIT(1)
- #define CDNS_I2C_IXR_COMP BIT(0)
-
- #define CDNS_I2C_IXR_ALL_INTR_MASK (CDNS_I2C_IXR_ARB_LOST | \
- CDNS_I2C_IXR_RX_UNF | \
- CDNS_I2C_IXR_TX_OVF | \
- CDNS_I2C_IXR_RX_OVF | \
- CDNS_I2C_IXR_SLV_RDY | \
- CDNS_I2C_IXR_TO | \
- CDNS_I2C_IXR_NACK | \
- CDNS_I2C_IXR_DATA | \
- CDNS_I2C_IXR_COMP)
-
- #define CDNS_I2C_IXR_ERR_INTR_MASK (CDNS_I2C_IXR_ARB_LOST | \
- CDNS_I2C_IXR_RX_UNF | \
- CDNS_I2C_IXR_TX_OVF | \
- CDNS_I2C_IXR_RX_OVF | \
- CDNS_I2C_IXR_NACK)
-
- #define CDNS_I2C_ENABLED_INTR_MASK (CDNS_I2C_IXR_ARB_LOST | \
- CDNS_I2C_IXR_RX_UNF | \
- CDNS_I2C_IXR_TX_OVF | \
- CDNS_I2C_IXR_RX_OVF | \
- CDNS_I2C_IXR_NACK | \
- CDNS_I2C_IXR_DATA | \
- CDNS_I2C_IXR_COMP)
-
- #define CDNS_I2C_IXR_SLAVE_INTR_MASK (CDNS_I2C_IXR_RX_UNF | \
- CDNS_I2C_IXR_TX_OVF | \
- CDNS_I2C_IXR_RX_OVF | \
- CDNS_I2C_IXR_TO | \
- CDNS_I2C_IXR_NACK | \
- CDNS_I2C_IXR_DATA | \
- CDNS_I2C_IXR_COMP)
-
- #define CDNS_I2C_TIMEOUT msecs_to_jiffies(1000)
- /* timeout for pm runtime autosuspend */
- #define CNDS_I2C_PM_TIMEOUT 1000 /* ms */
-
- #define CDNS_I2C_FIFO_DEPTH 16
- /* FIFO depth at which the DATA interrupt occurs */
- #define CDNS_I2C_DATA_INTR_DEPTH (CDNS_I2C_FIFO_DEPTH - 2)
- #define CDNS_I2C_MAX_TRANSFER_SIZE 255
- /* Transfer size in multiples of data interrupt depth */
- #define CDNS_I2C_TRANSFER_SIZE (CDNS_I2C_MAX_TRANSFER_SIZE - 3)
-
- #define DRIVER_NAME "cdns-i2c"
-
- #define CDNS_I2C_SPEED_MAX 400000
- #define CDNS_I2C_SPEED_DEFAULT 100000
-
- #define CDNS_I2C_DIVA_MAX 4
- #define CDNS_I2C_DIVB_MAX 64
-
- #define CDNS_I2C_TIMEOUT_MAX 0xFF
-
- #define CDNS_I2C_BROKEN_HOLD_BIT BIT(0)
-
- #define cdns_i2c_readreg(offset) readl_relaxed(id->membase + offset)
- #define cdns_i2c_writereg(val, offset) writel_relaxed(val, id->membase + offset)
-
- #if IS_ENABLED(CONFIG_I2C_SLAVE)
- /**
- * enum cdns_i2c_mode - I2C Controller current operating mode
- *
- * @CDNS_I2C_MODE_SLAVE: I2C controller operating in slave mode
- * @CDNS_I2C_MODE_MASTER: I2C Controller operating in master mode
- */
- enum cdns_i2c_mode {
- CDNS_I2C_MODE_SLAVE,
- CDNS_I2C_MODE_MASTER,
- };
-
- /**
- * enum cdns_i2c_slave_mode - Slave state when I2C is operating in slave mode
- *
- * @CDNS_I2C_SLAVE_STATE_IDLE: I2C slave idle
- * @CDNS_I2C_SLAVE_STATE_SEND: I2C slave sending data to master
- * @CDNS_I2C_SLAVE_STATE_RECV: I2C slave receiving data from master
- */
- enum cdns_i2c_slave_state {
- CDNS_I2C_SLAVE_STATE_IDLE,
- CDNS_I2C_SLAVE_STATE_SEND,
- CDNS_I2C_SLAVE_STATE_RECV,
- };
- #endif
-
- /**
- * struct cdns_i2c - I2C device private data structure
- *
- * @dev: Pointer to device structure
- * @membase: Base address of the I2C device
- * @adap: I2C adapter instance
- * @p_msg: Message pointer
- * @err_status: Error status in Interrupt Status Register
- * @xfer_done: Transfer complete status
- * @p_send_buf: Pointer to transmit buffer
- * @p_recv_buf: Pointer to receive buffer
- * @send_count: Number of bytes still expected to send
- * @recv_count: Number of bytes still expected to receive
- * @curr_recv_count: Number of bytes to be received in current transfer
- * @irq: IRQ number
- * @input_clk: Input clock to I2C controller
- * @i2c_clk: Maximum I2C clock speed
- * @bus_hold_flag: Flag used in repeated start for clearing HOLD bit
- * @clk: Pointer to struct clk
- * @clk_rate_change_nb: Notifier block for clock rate changes
- * @quirks: flag for broken hold bit usage in r1p10
- * @ctrl_reg: Cached value of the control register.
- * @rinfo: Structure holding recovery information.
- * @pinctrl: Pin control state holder.
- * @pinctrl_pins_default: Default pin control state.
- * @pinctrl_pins_gpio: GPIO pin control state.
- * @slave: Registered slave instance.
- * @dev_mode: I2C operating role(master/slave).
- * @slave_state: I2C Slave state(idle/read/write).
- */
- struct cdns_i2c {
- struct device *dev;
- void __iomem *membase;
- struct i2c_adapter adap;
- struct i2c_msg *p_msg;
- int err_status;
- struct completion xfer_done;
- unsigned char *p_send_buf;
- unsigned char *p_recv_buf;
- unsigned int send_count;
- unsigned int recv_count;
- unsigned int curr_recv_count;
- int irq;
- unsigned long input_clk;
- unsigned int i2c_clk;
- unsigned int bus_hold_flag;
- struct clk *clk;
- struct notifier_block clk_rate_change_nb;
- u32 quirks;
- u32 ctrl_reg;
- struct i2c_bus_recovery_info rinfo;
- struct pinctrl *pinctrl;
- struct pinctrl_state *pinctrl_pins_default;
- struct pinctrl_state *pinctrl_pins_gpio;
- #if IS_ENABLED(CONFIG_I2C_SLAVE)
- struct i2c_client *slave;
- enum cdns_i2c_mode dev_mode;
- enum cdns_i2c_slave_state slave_state;
- #endif
- };
-
- struct cdns_platform_data {
- u32 quirks;
- };
-
-
- static unsigned short i2c_rx_len=1;
- #define to_cdns_i2c(_nb) container_of(_nb, struct cdns_i2c, \
- clk_rate_change_nb)
-
- /**
- * cdns_i2c_clear_bus_hold - Clear bus hold bit
- * @id: Pointer to driver data struct
- *
- * Helper to clear the controller's bus hold bit.
- */
- static void cdns_i2c_clear_bus_hold(struct cdns_i2c *id)
- {
- u32 reg = cdns_i2c_readreg(CDNS_I2C_CR_OFFSET);
- if (reg & CDNS_I2C_CR_HOLD)
- cdns_i2c_writereg(reg & ~CDNS_I2C_CR_HOLD, CDNS_I2C_CR_OFFSET);
- }
-
- static inline bool cdns_is_holdquirk(struct cdns_i2c *id, bool hold_wrkaround)
- {
- return (hold_wrkaround &&
- (id->curr_recv_count == CDNS_I2C_FIFO_DEPTH + 1));
- }
-
- #if IS_ENABLED(CONFIG_I2C_SLAVE)
- static void cdns_i2c_set_mode(enum cdns_i2c_mode mode, struct cdns_i2c *id)
- {
- u32 reg;
-
- /* Disable all interrupts */
- cdns_i2c_writereg(CDNS_I2C_IXR_ALL_INTR_MASK, CDNS_I2C_IDR_OFFSET);
-
- /* Clear FIFO and transfer size */
- cdns_i2c_writereg(CDNS_I2C_CR_CLR_FIFO, CDNS_I2C_CR_OFFSET);
-
- /* Update device mode and state */
- id->dev_mode = mode;
- id->slave_state = CDNS_I2C_SLAVE_STATE_IDLE;
-
- switch (mode) {
- case CDNS_I2C_MODE_MASTER:
- /* Enable i2c master */
- cdns_i2c_writereg(id->ctrl_reg, CDNS_I2C_CR_OFFSET);
- break;
- case CDNS_I2C_MODE_SLAVE:
- /* Enable i2c slave */
- reg = cdns_i2c_readreg(CDNS_I2C_CR_OFFSET);
- reg &= ~CDNS_I2C_CR_SLAVE_EN_MASK;
-
- //cdns_i2c_writereg(reg, CDNS_I2C_CR_OFFSET);
- cdns_i2c_writereg(0x4c, CDNS_I2C_CR_OFFSET);
-
- /* Setting slave address */
- cdns_i2c_writereg(0x10,CDNS_I2C_ADDR_OFFSET);
-
- /* Enable slave send/receive interrupts */
- cdns_i2c_writereg(0x1|0x2|0x4|0x8|0x20|0x80,CDNS_I2C_IER_OFFSET);
-
- break;
- }
- }
-
- static void cdns_i2c_slave_rcv_data(struct cdns_i2c *id)
- {
- u8 bytes;
- unsigned char data;
- static int num=0;
-
- /* Prepare backend for data reception */
- if (id->slave_state == CDNS_I2C_SLAVE_STATE_IDLE) {
- id->slave_state = CDNS_I2C_SLAVE_STATE_RECV;
- //i2c_slave_event(id->slave, I2C_SLAVE_WRITE_REQUESTED, NULL);
- }
-
- /* Fetch number of bytes to receive */
- bytes = cdns_i2c_readreg(CDNS_I2C_XFER_SIZE_OFFSET);
- //printk("###zz debug###revc bytes is 0x%x\n",bytes);
- /* Read data and send to backend */
- while (bytes--) {
- data = cdns_i2c_readreg(CDNS_I2C_DATA_OFFSET);
- if(num<10)
- {
- printk("0x%x ",data);
- }
- num++;
- if (( i2c_rx_len != 0) && ( i2c_rx_len < ring_free_size(&i2c_recv_ring)))
- ring_put_at_free_space(&i2c_recv_ring, data, i2c_rx_len++);
-
- //i2c_slave_event(id->slave, I2C_SLAVE_WRITE_RECEIVED, &data);
- }
- //printk("\n");
-
- }
-
- static void cdns_i2c_slave_send_data(struct cdns_i2c *id)
- {
- u8 data;
-
- /* Prepare backend for data transmission */
- if (id->slave_state == CDNS_I2C_SLAVE_STATE_IDLE) {
- id->slave_state = CDNS_I2C_SLAVE_STATE_SEND;
- i2c_slave_event(id->slave, I2C_SLAVE_READ_REQUESTED, &data);
- } else {
- i2c_slave_event(id->slave, I2C_SLAVE_READ_PROCESSED, &data);
- }
-
- /* Send data over bus */
- cdns_i2c_writereg(data, CDNS_I2C_DATA_OFFSET);
- }
-
- /**
- * cdns_i2c_slave_isr - Interrupt handler for the I2C device in slave role
- * @ptr: Pointer to I2C device private data
- *
- * This function handles the data interrupt and transfer complete interrupt of
- * the I2C device in slave role.
- *
- * Return: IRQ_HANDLED always
- */
- static irqreturn_t cdns_i2c_slave_isr(void *ptr)
- {
- struct cdns_i2c *id = ptr;
- u8 byte0;
- unsigned int isr_status, i2c_status;
-
- /* Fetch the interrupt status */
- isr_status = cdns_i2c_readreg(CDNS_I2C_ISR_OFFSET);
- cdns_i2c_writereg(isr_status, CDNS_I2C_ISR_OFFSET);
-
- /* Ignore masked interrupts */
- isr_status &= ~cdns_i2c_readreg(CDNS_I2C_IMR_OFFSET);
-
- /* Fetch transfer mode (send/receive) */
- i2c_status = cdns_i2c_readreg(CDNS_I2C_SR_OFFSET);
-
- /* Handle data send/receive */
- if (i2c_status & CDNS_I2C_SR_RXRW) {
- /* Send data to master */
- if (isr_status & CDNS_I2C_IXR_DATA)
- cdns_i2c_slave_send_data(id);
-
- if (isr_status & CDNS_I2C_IXR_COMP) {
- id->slave_state = CDNS_I2C_SLAVE_STATE_IDLE;
- //i2c_slave_event(id->slave, I2C_SLAVE_STOP, NULL);
- }
- } else {
- /* Receive data from master */
- if (isr_status & CDNS_I2C_IXR_DATA)
- cdns_i2c_slave_rcv_data(id);
-
- if (isr_status & CDNS_I2C_IXR_COMP) {
- cdns_i2c_slave_rcv_data(id);
-
-
-
- if ((i2c_rx_len < ring_free_size(&i2c_recv_ring)) && (i2c_rx_len != 0))
- {
- /* Store the len byte (byte 0) */
- byte0 = i2c_rx_len - 1;
-
- ring_put_at_free_space(&i2c_recv_ring, byte0, 0);
-
- ring_set_free_space_ptr(&i2c_recv_ring,ring_get_free_space_ptr(&i2c_recv_ring, i2c_rx_len));
- }
-
- i2c_rx_len = 1;
- id->slave_state = CDNS_I2C_SLAVE_STATE_IDLE;
- //i2c_slave_event(id->slave, I2C_SLAVE_STOP, NULL);
- }
- }
-
- /* Master indicated xfer stop or fifo underflow/overflow */
- if (isr_status & (CDNS_I2C_IXR_NACK | CDNS_I2C_IXR_RX_OVF |
- CDNS_I2C_IXR_RX_UNF | CDNS_I2C_IXR_TX_OVF)) {
- id->slave_state = CDNS_I2C_SLAVE_STATE_IDLE;
- //i2c_slave_event(id->slave, I2C_SLAVE_STOP, NULL);
- cdns_i2c_writereg(CDNS_I2C_CR_CLR_FIFO, CDNS_I2C_CR_OFFSET);
- }
-
- return IRQ_HANDLED;
- }
- #endif
-
- /**
- * cdns_i2c_master_isr - Interrupt handler for the I2C device in master role
- * @ptr: Pointer to I2C device private data
- *
- * This function handles the data interrupt, transfer complete interrupt and
- * the error interrupts of the I2C device in master role.
- *
- * Return: IRQ_HANDLED always
- */
- static irqreturn_t cdns_i2c_master_isr(void *ptr)
- {
- unsigned int isr_status, avail_bytes, updatetx;
- unsigned int bytes_to_send;
- bool hold_quirk;
- struct cdns_i2c *id = ptr;
- /* Signal completion only after everything is updated */
- int done_flag = 0;
- irqreturn_t status = IRQ_NONE;
-
- isr_status = cdns_i2c_readreg(CDNS_I2C_ISR_OFFSET);
- cdns_i2c_writereg(isr_status, CDNS_I2C_ISR_OFFSET);
-
- /* Handling nack and arbitration lost interrupt */
- if (isr_status & (CDNS_I2C_IXR_NACK | CDNS_I2C_IXR_ARB_LOST)) {
- done_flag = 1;
- status = IRQ_HANDLED;
- }
-
- /*
- * Check if transfer size register needs to be updated again for a
- * large data receive operation.
- */
- updatetx = 0;
- if (id->recv_count > id->curr_recv_count)
- updatetx = 1;
-
- hold_quirk = (id->quirks & CDNS_I2C_BROKEN_HOLD_BIT) && updatetx;
-
- /* When receiving, handle data interrupt and completion interrupt */
- if (id->p_recv_buf &&
- ((isr_status & CDNS_I2C_IXR_COMP) ||
- (isr_status & CDNS_I2C_IXR_DATA))) {
- /* Read data if receive data valid is set */
- while (cdns_i2c_readreg(CDNS_I2C_SR_OFFSET) &
- CDNS_I2C_SR_RXDV) {
- /*
- * Clear hold bit that was set for FIFO control if
- * RX data left is less than FIFO depth, unless
- * repeated start is selected.
- */
- if ((id->recv_count < CDNS_I2C_FIFO_DEPTH) &&
- !id->bus_hold_flag)
- cdns_i2c_clear_bus_hold(id);
-
- *(id->p_recv_buf)++ =
- cdns_i2c_readreg(CDNS_I2C_DATA_OFFSET);
- id->recv_count--;
- id->curr_recv_count--;
-
- if (cdns_is_holdquirk(id, hold_quirk))
- break;
- }
-
- /*
- * The controller sends NACK to the slave when transfer size
- * register reaches zero without considering the HOLD bit.
- * This workaround is implemented for large data transfers to
- * maintain transfer size non-zero while performing a large
- * receive operation.
- */
- if (cdns_is_holdquirk(id, hold_quirk)) {
- /* wait while fifo is full */
- while (cdns_i2c_readreg(CDNS_I2C_XFER_SIZE_OFFSET) !=
- (id->curr_recv_count - CDNS_I2C_FIFO_DEPTH))
- ;
-
- /*
- * Check number of bytes to be received against maximum
- * transfer size and update register accordingly.
- */
- if (((int)(id->recv_count) - CDNS_I2C_FIFO_DEPTH) >
- CDNS_I2C_TRANSFER_SIZE) {
- cdns_i2c_writereg(CDNS_I2C_TRANSFER_SIZE,
- CDNS_I2C_XFER_SIZE_OFFSET);
- id->curr_recv_count = CDNS_I2C_TRANSFER_SIZE +
- CDNS_I2C_FIFO_DEPTH;
- } else {
- cdns_i2c_writereg(id->recv_count -
- CDNS_I2C_FIFO_DEPTH,
- CDNS_I2C_XFER_SIZE_OFFSET);
- id->curr_recv_count = id->recv_count;
- }
- } else if (id->recv_count && !hold_quirk &&
- !id->curr_recv_count) {
-
- /* Set the slave address in address register*/
- cdns_i2c_writereg(id->p_msg->addr & CDNS_I2C_ADDR_MASK,
- CDNS_I2C_ADDR_OFFSET);
-
- if (id->recv_count > CDNS_I2C_TRANSFER_SIZE) {
- cdns_i2c_writereg(CDNS_I2C_TRANSFER_SIZE,
- CDNS_I2C_XFER_SIZE_OFFSET);
- id->curr_recv_count = CDNS_I2C_TRANSFER_SIZE;
- } else {
- cdns_i2c_writereg(id->recv_count,
- CDNS_I2C_XFER_SIZE_OFFSET);
- id->curr_recv_count = id->recv_count;
- }
- }
-
- /* Clear hold (if not repeated start) and signal completion */
- if ((isr_status & CDNS_I2C_IXR_COMP) && !id->recv_count) {
- if (!id->bus_hold_flag)
- cdns_i2c_clear_bus_hold(id);
- done_flag = 1;
- }
-
- status = IRQ_HANDLED;
- }
-
- /* When sending, handle transfer complete interrupt */
- if ((isr_status & CDNS_I2C_IXR_COMP) && !id->p_recv_buf) {
- /*
- * If there is more data to be sent, calculate the
- * space available in FIFO and fill with that many bytes.
- */
- if (id->send_count) {
- avail_bytes = CDNS_I2C_FIFO_DEPTH -
- cdns_i2c_readreg(CDNS_I2C_XFER_SIZE_OFFSET);
- if (id->send_count > avail_bytes)
- bytes_to_send = avail_bytes;
- else
- bytes_to_send = id->send_count;
-
- while (bytes_to_send--) {
- cdns_i2c_writereg(
- (*(id->p_send_buf)++),
- CDNS_I2C_DATA_OFFSET);
- id->send_count--;
- }
- } else {
- /*
- * Signal the completion of transaction and
- * clear the hold bus bit if there are no
- * further messages to be processed.
- */
- done_flag = 1;
- }
- if (!id->send_count && !id->bus_hold_flag)
- cdns_i2c_clear_bus_hold(id);
-
- status = IRQ_HANDLED;
- }
-
- /* Handling Slave monitor mode interrupt */
- if (isr_status & CDNS_I2C_IXR_SLV_RDY) {
- unsigned int ctrl_reg;
- /* Read control register */
- ctrl_reg = cdns_i2c_readreg(CDNS_I2C_CR_OFFSET);
-
- /* Disable slave monitor mode */
- ctrl_reg &= ~CDNS_I2C_CR_SLVMON;
- cdns_i2c_writereg(ctrl_reg, CDNS_I2C_CR_OFFSET);
-
- /* Clear interrupt flag for slvmon mode */
- cdns_i2c_writereg(CDNS_I2C_IXR_SLV_RDY, CDNS_I2C_IDR_OFFSET);
-
- done_flag = 1;
- status = IRQ_HANDLED;
- }
-
- /* Update the status for errors */
- id->err_status = isr_status & CDNS_I2C_IXR_ERR_INTR_MASK;
- if (id->err_status)
- status = IRQ_HANDLED;
-
- if (done_flag)
- complete(&id->xfer_done);
-
- return status;
- }
-
- /**
- * cdns_i2c_isr - Interrupt handler for the I2C device
- * @irq: irq number for the I2C device
- * @ptr: void pointer to cdns_i2c structure
- *
- * This function passes the control to slave/master based on current role of
- * i2c controller.
- *
- * Return: IRQ_HANDLED always
- */
- static irqreturn_t cdns_i2c_isr(int irq, void *ptr)
- {
- #if IS_ENABLED(CONFIG_I2C_SLAVE)
- struct cdns_i2c *id = ptr;
-
- switch (id->dev_mode) {
- case CDNS_I2C_MODE_SLAVE:
- //printk("###i2c slave interrupt\n");
- dev_dbg(&id->adap.dev, "slave interrupt\n");
- cdns_i2c_slave_isr(ptr);
- break;
- case CDNS_I2C_MODE_MASTER:
- dev_dbg(&id->adap.dev, "master interrupt\n");
- cdns_i2c_master_isr(ptr);
- break;
- default:
- dev_dbg(&id->adap.dev, "undefined interrupt\n");
- break;
- }
- #else
- cdns_i2c_master_isr(ptr);
- #endif
- //cdns_i2c_writereg(CDNS_I2C_IXR_ALL_INTR_MASK, CDNS_I2C_IDR_OFFSET);
- return IRQ_HANDLED;
- }
-
- /**
- * cdns_i2c_mrecv - Prepare and start a master receive operation
- * @id: pointer to the i2c device structure
- */
- static void cdns_i2c_mrecv(struct cdns_i2c *id)
- {
- unsigned int ctrl_reg;
- unsigned int isr_status;
-
- id->p_recv_buf = id->p_msg->buf;
- id->recv_count = id->p_msg->len;
-
- /* Put the controller in master receive mode and clear the FIFO */
- ctrl_reg = cdns_i2c_readreg(CDNS_I2C_CR_OFFSET);
- ctrl_reg |= CDNS_I2C_CR_RW | CDNS_I2C_CR_CLR_FIFO;
-
- if (id->p_msg->flags & I2C_M_RECV_LEN)
- id->recv_count = I2C_SMBUS_BLOCK_MAX + 1;
-
- id->curr_recv_count = id->recv_count;
-
- /*
- * Check for the message size against FIFO depth and set the
- * 'hold bus' bit if it is greater than FIFO depth.
- */
- if (id->recv_count > CDNS_I2C_FIFO_DEPTH)
- ctrl_reg |= CDNS_I2C_CR_HOLD;
-
- cdns_i2c_writereg(ctrl_reg, CDNS_I2C_CR_OFFSET);
-
- /* Clear the interrupts in interrupt status register */
- isr_status = cdns_i2c_readreg(CDNS_I2C_ISR_OFFSET);
- cdns_i2c_writereg(isr_status, CDNS_I2C_ISR_OFFSET);
-
- /*
- * The no. of bytes to receive is checked against the limit of
- * max transfer size. Set transfer size register with no of bytes
- * receive if it is less than transfer size and transfer size if
- * it is more. Enable the interrupts.
- */
- if (id->recv_count > CDNS_I2C_TRANSFER_SIZE) {
- cdns_i2c_writereg(CDNS_I2C_TRANSFER_SIZE,
- CDNS_I2C_XFER_SIZE_OFFSET);
- id->curr_recv_count = CDNS_I2C_TRANSFER_SIZE;
- } else {
- cdns_i2c_writereg(id->recv_count, CDNS_I2C_XFER_SIZE_OFFSET);
- }
-
- /* Set the slave address in address register - triggers operation */
- cdns_i2c_writereg(CDNS_I2C_ENABLED_INTR_MASK, CDNS_I2C_IER_OFFSET);
- cdns_i2c_writereg(id->p_msg->addr & CDNS_I2C_ADDR_MASK,
- CDNS_I2C_ADDR_OFFSET);
- /* Clear the bus hold flag if bytes to receive is less than FIFO size */
- if (!id->bus_hold_flag &&
- ((id->p_msg->flags & I2C_M_RECV_LEN) != I2C_M_RECV_LEN) &&
- (id->recv_count <= CDNS_I2C_FIFO_DEPTH))
- cdns_i2c_clear_bus_hold(id);
- }
-
- /**
- * cdns_i2c_msend - Prepare and start a master send operation
- * @id: pointer to the i2c device
- */
- static void cdns_i2c_msend(struct cdns_i2c *id)
- {
- unsigned int avail_bytes;
- unsigned int bytes_to_send;
- unsigned int ctrl_reg;
- unsigned int isr_status;
-
- id->p_recv_buf = NULL;
- id->p_send_buf = id->p_msg->buf;
- id->send_count = id->p_msg->len;
-
- /* Set the controller in Master transmit mode and clear the FIFO. */
- ctrl_reg = cdns_i2c_readreg(CDNS_I2C_CR_OFFSET);
- ctrl_reg &= ~CDNS_I2C_CR_RW;
- ctrl_reg |= CDNS_I2C_CR_CLR_FIFO;
-
- /*
- * Check for the message size against FIFO depth and set the
- * 'hold bus' bit if it is greater than FIFO depth.
- */
- if (id->send_count > CDNS_I2C_FIFO_DEPTH)
- ctrl_reg |= CDNS_I2C_CR_HOLD;
- cdns_i2c_writereg(ctrl_reg, CDNS_I2C_CR_OFFSET);
-
- /* Clear the interrupts in interrupt status register. */
- isr_status = cdns_i2c_readreg(CDNS_I2C_ISR_OFFSET);
- cdns_i2c_writereg(isr_status, CDNS_I2C_ISR_OFFSET);
-
- /*
- * Calculate the space available in FIFO. Check the message length
- * against the space available, and fill the FIFO accordingly.
- * Enable the interrupts.
- */
- avail_bytes = CDNS_I2C_FIFO_DEPTH -
- cdns_i2c_readreg(CDNS_I2C_XFER_SIZE_OFFSET);
-
- if (id->send_count > avail_bytes)
- bytes_to_send = avail_bytes;
- else
- bytes_to_send = id->send_count;
-
- while (bytes_to_send--) {
- cdns_i2c_writereg((*(id->p_send_buf)++), CDNS_I2C_DATA_OFFSET);
- id->send_count--;
- }
-
- /*
- * Clear the bus hold flag if there is no more data
- * and if it is the last message.
- */
- if (!id->bus_hold_flag && !id->send_count)
- cdns_i2c_clear_bus_hold(id);
- /* Set the slave address in address register - triggers operation. */
- cdns_i2c_writereg(CDNS_I2C_ENABLED_INTR_MASK, CDNS_I2C_IER_OFFSET);
- cdns_i2c_writereg(id->p_msg->addr & CDNS_I2C_ADDR_MASK,
- CDNS_I2C_ADDR_OFFSET);
- }
-
- /**
- * cdns_i2c_slvmon - Handling Slav monitor mode feature
- * @id: pointer to the i2c device
- */
- static void cdns_i2c_slvmon(struct cdns_i2c *id)
- {
- unsigned int ctrl_reg;
- unsigned int isr_status;
-
- id->p_recv_buf = NULL;
- id->p_send_buf = id->p_msg->buf;
- id->send_count = id->p_msg->len;
-
- /* Clear the interrupts in interrupt status register. */
- isr_status = cdns_i2c_readreg(CDNS_I2C_ISR_OFFSET);
- cdns_i2c_writereg(isr_status, CDNS_I2C_ISR_OFFSET);
-
- /* Enable slvmon control reg */
- ctrl_reg = cdns_i2c_readreg(CDNS_I2C_CR_OFFSET);
- ctrl_reg |= CDNS_I2C_CR_MS | CDNS_I2C_CR_NEA | CDNS_I2C_CR_SLVMON
- | CDNS_I2C_CR_CLR_FIFO;
- ctrl_reg &= ~(CDNS_I2C_CR_RW);
- cdns_i2c_writereg(ctrl_reg, CDNS_I2C_CR_OFFSET);
-
- /* Initialize slvmon reg */
- cdns_i2c_writereg(0xF, CDNS_I2C_SLV_PAUSE_OFFSET);
-
- /* Set the slave address to start the slave address transmission */
- cdns_i2c_writereg(id->p_msg->addr, CDNS_I2C_ADDR_OFFSET);
-
- /* Setup slvmon interrupt flag */
- cdns_i2c_writereg(CDNS_I2C_IXR_SLV_RDY, CDNS_I2C_IER_OFFSET);
- }
-
- /**
- * cdns_i2c_master_reset - Reset the interface
- * @adap: pointer to the i2c adapter driver instance
- *
- * This function cleanup the fifos, clear the hold bit and status
- * and disable the interrupts.
- */
- static void cdns_i2c_master_reset(struct i2c_adapter *adap)
- {
- struct cdns_i2c *id = adap->algo_data;
- u32 regval;
-
- /* Disable the interrupts */
- cdns_i2c_writereg(CDNS_I2C_IXR_ALL_INTR_MASK, CDNS_I2C_IDR_OFFSET);
- /* Clear the hold bit and fifos */
- regval = cdns_i2c_readreg(CDNS_I2C_CR_OFFSET);
- regval &= ~(CDNS_I2C_CR_HOLD | CDNS_I2C_CR_SLVMON);
- regval |= CDNS_I2C_CR_CLR_FIFO;
- cdns_i2c_writereg(regval, CDNS_I2C_CR_OFFSET);
- /* Update the transfercount register to zero */
- cdns_i2c_writereg(0, CDNS_I2C_XFER_SIZE_OFFSET);
- /* Clear the interrupt status register */
- regval = cdns_i2c_readreg(CDNS_I2C_ISR_OFFSET);
- cdns_i2c_writereg(regval, CDNS_I2C_ISR_OFFSET);
- /* Clear the status register */
- regval = cdns_i2c_readreg(CDNS_I2C_SR_OFFSET);
- cdns_i2c_writereg(regval, CDNS_I2C_SR_OFFSET);
- }
-
- static int cdns_i2c_process_msg(struct cdns_i2c *id, struct i2c_msg *msg,
- struct i2c_adapter *adap)
- {
- unsigned long time_left;
- u32 reg;
-
- id->p_msg = msg;
- id->err_status = 0;
- reinit_completion(&id->xfer_done);
-
- /* Check for the TEN Bit mode on each msg */
- reg = cdns_i2c_readreg(CDNS_I2C_CR_OFFSET);
- if (msg->flags & I2C_M_TEN) {
- if (reg & CDNS_I2C_CR_NEA)
- cdns_i2c_writereg(reg & ~CDNS_I2C_CR_NEA,
- CDNS_I2C_CR_OFFSET);
- } else {
- if (!(reg & CDNS_I2C_CR_NEA))
- cdns_i2c_writereg(reg | CDNS_I2C_CR_NEA,
- CDNS_I2C_CR_OFFSET);
- }
- /* Check for zero length - Slave monitor mode */
- if (msg->len == 0)
- cdns_i2c_slvmon(id);
- /* Check for the R/W flag on each msg */
- else if (msg->flags & I2C_M_RD)
- cdns_i2c_mrecv(id);
- else
- cdns_i2c_msend(id);
-
- /* Wait for the signal of completion */
- time_left = wait_for_completion_timeout(&id->xfer_done, adap->timeout);
- if (time_left == 0) {
- i2c_recover_bus(adap);
- cdns_i2c_master_reset(adap);
- dev_err(id->adap.dev.parent,
- "timeout waiting on completion\n");
- return -ETIMEDOUT;
- }
-
- cdns_i2c_writereg(CDNS_I2C_IXR_ALL_INTR_MASK,
- CDNS_I2C_IDR_OFFSET);
-
- /* If it is bus arbitration error, try again */
- if (id->err_status & CDNS_I2C_IXR_ARB_LOST)
- return -EAGAIN;
-
- return 0;
- }
-
- /**
- * cdns_i2c_master_xfer - The main i2c transfer function
- * @adap: pointer to the i2c adapter driver instance
- * @msgs: pointer to the i2c message structure
- * @num: the number of messages to transfer
- *
- * Initiates the send/recv activity based on the transfer message received.
- *
- * Return: number of msgs processed on success, negative error otherwise
- */
- static int cdns_i2c_master_xfer(struct i2c_adapter *adap, struct i2c_msg *msgs,
- int num)
- {
- int ret, count;
- u32 reg;
- struct cdns_i2c *id = adap->algo_data;
- bool hold_quirk;
- #if IS_ENABLED(CONFIG_I2C_SLAVE)
- bool change_role = false;
- #endif
-
- ret = pm_runtime_get_sync(id->dev);
- if (ret < 0)
- return ret;
-
- #if IS_ENABLED(CONFIG_I2C_SLAVE)
- /* Check i2c operating mode and switch if possible */
- if (id->dev_mode == CDNS_I2C_MODE_SLAVE) {
- if (id->slave_state != CDNS_I2C_SLAVE_STATE_IDLE)
- return -EAGAIN;
-
- /* Set mode to master */
- cdns_i2c_set_mode(CDNS_I2C_MODE_MASTER, id);
-
- /* Mark flag to change role once xfer is completed */
- change_role = true;
- }
- #endif
-
- /* Check if the bus is free */
- if (msgs->len)
- if (cdns_i2c_readreg(CDNS_I2C_SR_OFFSET) & CDNS_I2C_SR_BA) {
- ret = -EAGAIN;
- goto out;
- }
-
- hold_quirk = !!(id->quirks & CDNS_I2C_BROKEN_HOLD_BIT);
- /*
- * Set the flag to one when multiple messages are to be
- * processed with a repeated start.
- */
- if (num > 1) {
- /*
- * This controller does not give completion interrupt after a
- * master receive message if HOLD bit is set (repeated start),
- * resulting in SW timeout. Hence, if a receive message is
- * followed by any other message, an error is returned
- * indicating that this sequence is not supported.
- */
- for (count = 0; (count < num - 1 && hold_quirk); count++) {
- if (msgs[count].flags & I2C_M_RD) {
- dev_warn(adap->dev.parent,
- "Can't do repeated start after a receive message\n");
- ret = -EOPNOTSUPP;
- goto out;
- }
- }
- id->bus_hold_flag = 1;
- reg = cdns_i2c_readreg(CDNS_I2C_CR_OFFSET);
- reg |= CDNS_I2C_CR_HOLD;
- cdns_i2c_writereg(reg, CDNS_I2C_CR_OFFSET);
- } else {
- id->bus_hold_flag = 0;
- }
-
- /* Process the msg one by one */
- for (count = 0; count < num; count++, msgs++) {
- if (count == (num - 1))
- id->bus_hold_flag = 0;
-
- ret = cdns_i2c_process_msg(id, msgs, adap);
- if (ret)
- goto out;
-
- /* Report the other error interrupts to application */
- if (id->err_status) {
- cdns_i2c_master_reset(adap);
-
- if (id->err_status & CDNS_I2C_IXR_NACK) {
- ret = -ENXIO;
- goto out;
- }
- ret = -EIO;
- goto out;
- }
- }
-
- ret = num;
-
- #if IS_ENABLED(CONFIG_I2C_SLAVE)
- /* Switch i2c mode to slave */
- if (change_role)
- cdns_i2c_set_mode(CDNS_I2C_MODE_SLAVE, id);
- #endif
-
- out:
- pm_runtime_mark_last_busy(id->dev);
- pm_runtime_put_autosuspend(id->dev);
- return ret;
- }
-
- /**
- * cdns_i2c_func - Returns the supported features of the I2C driver
- * @adap: pointer to the i2c adapter structure
- *
- * Return: 32 bit value, each bit corresponding to a feature
- */
- static u32 cdns_i2c_func(struct i2c_adapter *adap)
- {
- u32 func = I2C_FUNC_I2C | I2C_FUNC_10BIT_ADDR |
- (I2C_FUNC_SMBUS_EMUL & ~I2C_FUNC_SMBUS_QUICK) |
- I2C_FUNC_SMBUS_BLOCK_DATA;
-
- #if IS_ENABLED(CONFIG_I2C_SLAVE)
- func |= I2C_FUNC_SLAVE;
- #endif
-
- return func;
- }
-
- static int cdns_i2c_bus_busy(struct cdns_i2c *id)
- {
-
- u32 StatusReg;
- int Status;
-
- StatusReg = cdns_i2c_readreg(CDNS_I2C_SR_OFFSET);
-
- if ((StatusReg & CDNS_I2C_SR_BA) != 0x0U)
- {
- Status = 0;
- }
- else
- {
- Status = -1;
- }
- return Status;
-
- }
-
- #if IS_ENABLED(CONFIG_I2C_SLAVE)
- static int cdns_reg_slave(struct i2c_client *slave)
- {
- int ret;
- struct cdns_i2c *id = container_of(slave->adapter, struct cdns_i2c,adap);
-
- if (id-&
来源:CSDN
作者:kunkliu
链接:https://blog.csdn.net/kunkliu/article/details/103567604