1
0
Fork 0

Merge branch 'i2c/for-next' of git://git.kernel.org/pub/scm/linux/kernel/git/wsa/linux

Pull i2c updates from Wolfram Sang:
 "Highlights from the I2C subsystem for 3.18:

   - new drivers for Axxia AM55xx, and Hisilicon hix5hd2 SoC.

   - designware driver gained AMD support, exynos gained exynos7 support

  The rest is usual driver stuff.  Hopefully no lowlights this time"

* 'i2c/for-next' of git://git.kernel.org/pub/scm/linux/kernel/git/wsa/linux:
  i2c: i801: Add Device IDs for Intel Sunrise Point PCH
  i2c: hix5hd2: add i2c controller driver
  i2c-imx: Disable the clock on probe failure
  i2c: designware: Add support for AMD I2C controller
  i2c: designware: Rework probe() to get clock a bit later
  i2c: designware: Default to fast mode in case of ACPI
  i2c: axxia: Add I2C driver for AXM55xx
  i2c: exynos: add support for HSI2C module on Exynos7
  i2c: mxs: detect No Slave Ack on SELECT in PIO mode
  i2c: cros_ec: Remove EC_I2C_FLAG_10BIT
  i2c: cros-ec-tunnel: Add of match table
  i2c: rcar: remove sign-compare flaw
  i2c: ismt: Use minimum descriptor size
  i2c: imx: Add arbitration lost check
  i2c: rk3x: Remove unlikely() annotations
  i2c: rcar: check for no IRQ in rcar_i2c_irq()
  i2c: rcar: make rcar_i2c_prepare_msg() *void*
  i2c: rcar: simplify check for last message
  i2c: designware: add support of platform data to set I2C mode
  i2c: designware: add support of I2C standard mode
hifive-unleashed-5.1
Linus Torvalds 2014-10-19 12:50:44 -07:00
commit 278f1d0730
19 changed files with 1404 additions and 51 deletions

View File

@ -0,0 +1,30 @@
LSI Axxia I2C
Required properties :
- compatible : Must be "lsi,api2c"
- reg : Offset and length of the register set for the device
- interrupts : the interrupt specifier
- #address-cells : Must be <1>;
- #size-cells : Must be <0>;
- clock-names : Must contain "i2c".
- clocks: Must contain an entry for each name in clock-names. See the common
clock bindings.
Optional properties :
- clock-frequency : Desired I2C bus clock frequency in Hz. If not specified,
the default 100 kHz frequency will be used. As only Normal and Fast modes
are supported, possible values are 100000 and 400000.
Example :
i2c@02010084000 {
compatible = "lsi,api2c";
device_type = "i2c";
#address-cells = <1>;
#size-cells = <0>;
reg = <0x20 0x10084000 0x00 0x1000>;
interrupts = <0 19 4>;
clocks = <&clk_per>;
clock-names = "i2c";
clock-frequency = <400000>;
};

View File

@ -12,6 +12,8 @@ Required properties:
on Exynos5250 and Exynos5420 SoCs.
-> "samsung,exynos5260-hsi2c", for i2c compatible with HSI2C available
on Exynos5260 SoCs.
-> "samsung,exynos7-hsi2c", for i2c compatible with HSI2C available
on Exynos7 SoCs.
- reg: physical base address of the controller and length of memory mapped
region.

View File

@ -0,0 +1,24 @@
I2C for Hisilicon hix5hd2 chipset platform
Required properties:
- compatible: Must be "hisilicon,hix5hd2-i2c"
- reg: physical base address of the controller and length of memory mapped
region.
- interrupts: interrupt number to the cpu.
- #address-cells = <1>;
- #size-cells = <0>;
- clocks: phandles to input clocks.
Optional properties:
- clock-frequency: Desired I2C bus frequency in Hz, otherwise defaults to 100000
- Child nodes conforming to i2c bus binding
Examples:
I2C0@f8b10000 {
compatible = "hisilicon,hix5hd2-i2c";
reg = <0xf8b10000 0x1000>;
interrupts = <0 38 4>;
clocks = <&clock HIX5HD2_I2C0_RST>;
#address-cells = <1>;
#size-cells = <0>;
}

View File

@ -28,6 +28,7 @@ Supported adapters:
* Intel Wildcat Point (PCH)
* Intel Wildcat Point-LP (PCH)
* Intel BayTrail (SOC)
* Intel Sunrise Point-H (PCH)
Datasheets: Publicly available at the Intel website
On Intel Patsburg and later chipsets, both the normal host SMBus controller

View File

@ -77,6 +77,16 @@ config I2C_AMD8111
This driver can also be built as a module. If so, the module
will be called i2c-amd8111.
config I2C_HIX5HD2
tristate "Hix5hd2 high-speed I2C driver"
depends on ARCH_HIX5HD2
help
Say Y here to include support for high-speed I2C controller in the
Hisilicon based hix5hd2 SoCs.
This driver can also be built as a module. If so, the module
will be called i2c-hix5hd2.
config I2C_I801
tristate "Intel 82801 (ICH/PCH)"
depends on PCI
@ -112,6 +122,7 @@ config I2C_I801
Wildcat Point (PCH)
Wildcat Point-LP (PCH)
BayTrail (SOC)
Sunrise Point-H (PCH)
This driver can also be built as a module. If so, the module
will be called i2c-i801.
@ -337,6 +348,17 @@ config I2C_AU1550
This driver can also be built as a module. If so, the module
will be called i2c-au1550.
config I2C_AXXIA
tristate "Axxia I2C controller"
depends on ARCH_AXXIA || COMPILE_TEST
default ARCH_AXXIA
help
Say yes if you want to support the I2C bus on Axxia platforms.
Please note that this controller is limited to transfers of maximum
255 bytes in length. Any attempt to to a larger transfer will return
an error.
config I2C_BCM2835
tristate "Broadcom BCM2835 I2C controller"
depends on ARCH_BCM2835
@ -423,6 +445,7 @@ config I2C_DESIGNWARE_CORE
config I2C_DESIGNWARE_PLATFORM
tristate "Synopsys DesignWare Platform"
select I2C_DESIGNWARE_CORE
depends on (ACPI && COMMON_CLK) || !ACPI
help
If you say yes to this option, support will be included for the
Synopsys DesignWare I2C adapter. Only master mode is supported.
@ -465,7 +488,7 @@ config I2C_EG20T
config I2C_EXYNOS5
tristate "Exynos5 high-speed I2C driver"
depends on ARCH_EXYNOS5 && OF
depends on ARCH_EXYNOS && OF
default y
help
High-speed I2C controller on Exynos5 based Samsung SoCs.

View File

@ -31,6 +31,7 @@ obj-$(CONFIG_I2C_POWERMAC) += i2c-powermac.o
# Embedded system I2C/SMBus host controller drivers
obj-$(CONFIG_I2C_AT91) += i2c-at91.o
obj-$(CONFIG_I2C_AU1550) += i2c-au1550.o
obj-$(CONFIG_I2C_AXXIA) += i2c-axxia.o
obj-$(CONFIG_I2C_BCM2835) += i2c-bcm2835.o
obj-$(CONFIG_I2C_BLACKFIN_TWI) += i2c-bfin-twi.o
obj-$(CONFIG_I2C_CADENCE) += i2c-cadence.o
@ -47,6 +48,7 @@ obj-$(CONFIG_I2C_EG20T) += i2c-eg20t.o
obj-$(CONFIG_I2C_EXYNOS5) += i2c-exynos5.o
obj-$(CONFIG_I2C_GPIO) += i2c-gpio.o
obj-$(CONFIG_I2C_HIGHLANDER) += i2c-highlander.o
obj-$(CONFIG_I2C_HIX5HD2) += i2c-hix5hd2.o
obj-$(CONFIG_I2C_IBM_IIC) += i2c-ibm_iic.o
obj-$(CONFIG_I2C_IMX) += i2c-imx.o
obj-$(CONFIG_I2C_IOP3XX) += i2c-iop3xx.o

View File

@ -0,0 +1,559 @@
/*
* This driver implements I2C master functionality using the LSI API2C
* controller.
*
* NOTE: The controller has a limitation in that it can only do transfers of
* maximum 255 bytes at a time. If a larger transfer is attempted, error code
* (-EINVAL) is returned.
*
* This software is licensed under the terms of the GNU General Public
* License version 2, as published by the Free Software Foundation, and
* may be copied, distributed, and modified under those terms.
*/
#include <linux/clk.h>
#include <linux/clkdev.h>
#include <linux/err.h>
#include <linux/i2c.h>
#include <linux/init.h>
#include <linux/interrupt.h>
#include <linux/module.h>
#include <linux/io.h>
#include <linux/kernel.h>
#include <linux/platform_device.h>
#define SCL_WAIT_TIMEOUT_NS 25000000
#define I2C_XFER_TIMEOUT (msecs_to_jiffies(250))
#define I2C_STOP_TIMEOUT (msecs_to_jiffies(100))
#define FIFO_SIZE 8
#define GLOBAL_CONTROL 0x00
#define GLOBAL_MST_EN BIT(0)
#define GLOBAL_SLV_EN BIT(1)
#define GLOBAL_IBML_EN BIT(2)
#define INTERRUPT_STATUS 0x04
#define INTERRUPT_ENABLE 0x08
#define INT_SLV BIT(1)
#define INT_MST BIT(0)
#define WAIT_TIMER_CONTROL 0x0c
#define WT_EN BIT(15)
#define WT_VALUE(_x) ((_x) & 0x7fff)
#define IBML_TIMEOUT 0x10
#define IBML_LOW_MEXT 0x14
#define IBML_LOW_SEXT 0x18
#define TIMER_CLOCK_DIV 0x1c
#define I2C_BUS_MONITOR 0x20
#define SOFT_RESET 0x24
#define MST_COMMAND 0x28
#define CMD_BUSY (1<<3)
#define CMD_MANUAL (0x00 | CMD_BUSY)
#define CMD_AUTO (0x01 | CMD_BUSY)
#define MST_RX_XFER 0x2c
#define MST_TX_XFER 0x30
#define MST_ADDR_1 0x34
#define MST_ADDR_2 0x38
#define MST_DATA 0x3c
#define MST_TX_FIFO 0x40
#define MST_RX_FIFO 0x44
#define MST_INT_ENABLE 0x48
#define MST_INT_STATUS 0x4c
#define MST_STATUS_RFL (1 << 13) /* RX FIFO serivce */
#define MST_STATUS_TFL (1 << 12) /* TX FIFO service */
#define MST_STATUS_SNS (1 << 11) /* Manual mode done */
#define MST_STATUS_SS (1 << 10) /* Automatic mode done */
#define MST_STATUS_SCC (1 << 9) /* Stop complete */
#define MST_STATUS_IP (1 << 8) /* Invalid parameter */
#define MST_STATUS_TSS (1 << 7) /* Timeout */
#define MST_STATUS_AL (1 << 6) /* Arbitration lost */
#define MST_STATUS_ND (1 << 5) /* NAK on data phase */
#define MST_STATUS_NA (1 << 4) /* NAK on address phase */
#define MST_STATUS_NAK (MST_STATUS_NA | \
MST_STATUS_ND)
#define MST_STATUS_ERR (MST_STATUS_NAK | \
MST_STATUS_AL | \
MST_STATUS_IP | \
MST_STATUS_TSS)
#define MST_TX_BYTES_XFRD 0x50
#define MST_RX_BYTES_XFRD 0x54
#define SCL_HIGH_PERIOD 0x80
#define SCL_LOW_PERIOD 0x84
#define SPIKE_FLTR_LEN 0x88
#define SDA_SETUP_TIME 0x8c
#define SDA_HOLD_TIME 0x90
/**
* axxia_i2c_dev - I2C device context
* @base: pointer to register struct
* @msg: pointer to current message
* @msg_xfrd: number of bytes transferred in msg
* @msg_err: error code for completed message
* @msg_complete: xfer completion object
* @dev: device reference
* @adapter: core i2c abstraction
* @i2c_clk: clock reference for i2c input clock
* @bus_clk_rate: current i2c bus clock rate
*/
struct axxia_i2c_dev {
void __iomem *base;
struct i2c_msg *msg;
size_t msg_xfrd;
int msg_err;
struct completion msg_complete;
struct device *dev;
struct i2c_adapter adapter;
struct clk *i2c_clk;
u32 bus_clk_rate;
};
static void i2c_int_disable(struct axxia_i2c_dev *idev, u32 mask)
{
u32 int_en;
int_en = readl(idev->base + MST_INT_ENABLE);
writel(int_en & ~mask, idev->base + MST_INT_ENABLE);
}
static void i2c_int_enable(struct axxia_i2c_dev *idev, u32 mask)
{
u32 int_en;
int_en = readl(idev->base + MST_INT_ENABLE);
writel(int_en | mask, idev->base + MST_INT_ENABLE);
}
/**
* ns_to_clk - Convert time (ns) to clock cycles for the given clock frequency.
*/
static u32 ns_to_clk(u64 ns, u32 clk_mhz)
{
return div_u64(ns * clk_mhz, 1000);
}
static int axxia_i2c_init(struct axxia_i2c_dev *idev)
{
u32 divisor = clk_get_rate(idev->i2c_clk) / idev->bus_clk_rate;
u32 clk_mhz = clk_get_rate(idev->i2c_clk) / 1000000;
u32 t_setup;
u32 t_high, t_low;
u32 tmo_clk;
u32 prescale;
unsigned long timeout;
dev_dbg(idev->dev, "rate=%uHz per_clk=%uMHz -> ratio=1:%u\n",
idev->bus_clk_rate, clk_mhz, divisor);
/* Reset controller */
writel(0x01, idev->base + SOFT_RESET);
timeout = jiffies + msecs_to_jiffies(100);
while (readl(idev->base + SOFT_RESET) & 1) {
if (time_after(jiffies, timeout)) {
dev_warn(idev->dev, "Soft reset failed\n");
break;
}
}
/* Enable Master Mode */
writel(0x1, idev->base + GLOBAL_CONTROL);
if (idev->bus_clk_rate <= 100000) {
/* Standard mode SCL 50/50, tSU:DAT = 250 ns */
t_high = divisor * 1 / 2;
t_low = divisor * 1 / 2;
t_setup = ns_to_clk(250, clk_mhz);
} else {
/* Fast mode SCL 33/66, tSU:DAT = 100 ns */
t_high = divisor * 1 / 3;
t_low = divisor * 2 / 3;
t_setup = ns_to_clk(100, clk_mhz);
}
/* SCL High Time */
writel(t_high, idev->base + SCL_HIGH_PERIOD);
/* SCL Low Time */
writel(t_low, idev->base + SCL_LOW_PERIOD);
/* SDA Setup Time */
writel(t_setup, idev->base + SDA_SETUP_TIME);
/* SDA Hold Time, 300ns */
writel(ns_to_clk(300, clk_mhz), idev->base + SDA_HOLD_TIME);
/* Filter <50ns spikes */
writel(ns_to_clk(50, clk_mhz), idev->base + SPIKE_FLTR_LEN);
/* Configure Time-Out Registers */
tmo_clk = ns_to_clk(SCL_WAIT_TIMEOUT_NS, clk_mhz);
/* Find prescaler value that makes tmo_clk fit in 15-bits counter. */
for (prescale = 0; prescale < 15; ++prescale) {
if (tmo_clk <= 0x7fff)
break;
tmo_clk >>= 1;
}
if (tmo_clk > 0x7fff)
tmo_clk = 0x7fff;
/* Prescale divider (log2) */
writel(prescale, idev->base + TIMER_CLOCK_DIV);
/* Timeout in divided clocks */
writel(WT_EN | WT_VALUE(tmo_clk), idev->base + WAIT_TIMER_CONTROL);
/* Mask all master interrupt bits */
i2c_int_disable(idev, ~0);
/* Interrupt enable */
writel(0x01, idev->base + INTERRUPT_ENABLE);
return 0;
}
static int i2c_m_rd(const struct i2c_msg *msg)
{
return (msg->flags & I2C_M_RD) != 0;
}
static int i2c_m_ten(const struct i2c_msg *msg)
{
return (msg->flags & I2C_M_TEN) != 0;
}
static int i2c_m_recv_len(const struct i2c_msg *msg)
{
return (msg->flags & I2C_M_RECV_LEN) != 0;
}
/**
* axxia_i2c_empty_rx_fifo - Fetch data from RX FIFO and update SMBus block
* transfer length if this is the first byte of such a transfer.
*/
static int axxia_i2c_empty_rx_fifo(struct axxia_i2c_dev *idev)
{
struct i2c_msg *msg = idev->msg;
size_t rx_fifo_avail = readl(idev->base + MST_RX_FIFO);
int bytes_to_transfer = min(rx_fifo_avail, msg->len - idev->msg_xfrd);
while (bytes_to_transfer-- > 0) {
int c = readl(idev->base + MST_DATA);
if (idev->msg_xfrd == 0 && i2c_m_recv_len(msg)) {
/*
* Check length byte for SMBus block read
*/
if (c <= 0 || c > I2C_SMBUS_BLOCK_MAX) {
idev->msg_err = -EPROTO;
i2c_int_disable(idev, ~0);
complete(&idev->msg_complete);
break;
}
msg->len = 1 + c;
writel(msg->len, idev->base + MST_RX_XFER);
}
msg->buf[idev->msg_xfrd++] = c;
}
return 0;
}
/**
* axxia_i2c_fill_tx_fifo - Fill TX FIFO from current message buffer.
* @return: Number of bytes left to transfer.
*/
static int axxia_i2c_fill_tx_fifo(struct axxia_i2c_dev *idev)
{
struct i2c_msg *msg = idev->msg;
size_t tx_fifo_avail = FIFO_SIZE - readl(idev->base + MST_TX_FIFO);
int bytes_to_transfer = min(tx_fifo_avail, msg->len - idev->msg_xfrd);
int ret = msg->len - idev->msg_xfrd - bytes_to_transfer;
while (bytes_to_transfer-- > 0)
writel(msg->buf[idev->msg_xfrd++], idev->base + MST_DATA);
return ret;
}
static irqreturn_t axxia_i2c_isr(int irq, void *_dev)
{
struct axxia_i2c_dev *idev = _dev;
u32 status;
if (!(readl(idev->base + INTERRUPT_STATUS) & INT_MST))
return IRQ_NONE;
/* Read interrupt status bits */
status = readl(idev->base + MST_INT_STATUS);
if (!idev->msg) {
dev_warn(idev->dev, "unexpected interrupt\n");
goto out;
}
/* RX FIFO needs service? */
if (i2c_m_rd(idev->msg) && (status & MST_STATUS_RFL))
axxia_i2c_empty_rx_fifo(idev);
/* TX FIFO needs service? */
if (!i2c_m_rd(idev->msg) && (status & MST_STATUS_TFL)) {
if (axxia_i2c_fill_tx_fifo(idev) == 0)
i2c_int_disable(idev, MST_STATUS_TFL);
}
if (status & MST_STATUS_SCC) {
/* Stop completed */
i2c_int_disable(idev, ~0);
complete(&idev->msg_complete);
} else if (status & MST_STATUS_SNS) {
/* Transfer done */
i2c_int_disable(idev, ~0);
if (i2c_m_rd(idev->msg) && idev->msg_xfrd < idev->msg->len)
axxia_i2c_empty_rx_fifo(idev);
complete(&idev->msg_complete);
} else if (unlikely(status & MST_STATUS_ERR)) {
/* Transfer error */
i2c_int_disable(idev, ~0);
if (status & MST_STATUS_AL)
idev->msg_err = -EAGAIN;
else if (status & MST_STATUS_NAK)
idev->msg_err = -ENXIO;
else
idev->msg_err = -EIO;
dev_dbg(idev->dev, "error %#x, addr=%#x rx=%u/%u tx=%u/%u\n",
status,
idev->msg->addr,
readl(idev->base + MST_RX_BYTES_XFRD),
readl(idev->base + MST_RX_XFER),
readl(idev->base + MST_TX_BYTES_XFRD),
readl(idev->base + MST_TX_XFER));
complete(&idev->msg_complete);
}
out:
/* Clear interrupt */
writel(INT_MST, idev->base + INTERRUPT_STATUS);
return IRQ_HANDLED;
}
static int axxia_i2c_xfer_msg(struct axxia_i2c_dev *idev, struct i2c_msg *msg)
{
u32 int_mask = MST_STATUS_ERR | MST_STATUS_SNS;
u32 rx_xfer, tx_xfer;
u32 addr_1, addr_2;
int ret;
if (msg->len > 255) {
dev_warn(idev->dev, "unsupported length %u\n", msg->len);
return -EINVAL;
}
idev->msg = msg;
idev->msg_xfrd = 0;
idev->msg_err = 0;
reinit_completion(&idev->msg_complete);
if (i2c_m_ten(msg)) {
/* 10-bit address
* addr_1: 5'b11110 | addr[9:8] | (R/nW)
* addr_2: addr[7:0]
*/
addr_1 = 0xF0 | ((msg->addr >> 7) & 0x06);
addr_2 = msg->addr & 0xFF;
} else {
/* 7-bit address
* addr_1: addr[6:0] | (R/nW)
* addr_2: dont care
*/
addr_1 = (msg->addr << 1) & 0xFF;
addr_2 = 0;
}
if (i2c_m_rd(msg)) {
/* I2C read transfer */
rx_xfer = i2c_m_recv_len(msg) ? I2C_SMBUS_BLOCK_MAX : msg->len;
tx_xfer = 0;
addr_1 |= 1; /* Set the R/nW bit of the address */
} else {
/* I2C write transfer */
rx_xfer = 0;
tx_xfer = msg->len;
}
writel(rx_xfer, idev->base + MST_RX_XFER);
writel(tx_xfer, idev->base + MST_TX_XFER);
writel(addr_1, idev->base + MST_ADDR_1);
writel(addr_2, idev->base + MST_ADDR_2);
if (i2c_m_rd(msg))
int_mask |= MST_STATUS_RFL;
else if (axxia_i2c_fill_tx_fifo(idev) != 0)
int_mask |= MST_STATUS_TFL;
/* Start manual mode */
writel(CMD_MANUAL, idev->base + MST_COMMAND);
i2c_int_enable(idev, int_mask);
ret = wait_for_completion_timeout(&idev->msg_complete,
I2C_XFER_TIMEOUT);
i2c_int_disable(idev, int_mask);
if (readl(idev->base + MST_COMMAND) & CMD_BUSY)
dev_warn(idev->dev, "busy after xfer\n");
if (ret == 0)
idev->msg_err = -ETIMEDOUT;
if (unlikely(idev->msg_err) && idev->msg_err != -ENXIO)
axxia_i2c_init(idev);
return idev->msg_err;
}
static int axxia_i2c_stop(struct axxia_i2c_dev *idev)
{
u32 int_mask = MST_STATUS_ERR | MST_STATUS_SCC;
int ret;
reinit_completion(&idev->msg_complete);
/* Issue stop */
writel(0xb, idev->base + MST_COMMAND);
i2c_int_enable(idev, int_mask);
ret = wait_for_completion_timeout(&idev->msg_complete,
I2C_STOP_TIMEOUT);
i2c_int_disable(idev, int_mask);
if (ret == 0)
return -ETIMEDOUT;
if (readl(idev->base + MST_COMMAND) & CMD_BUSY)
dev_warn(idev->dev, "busy after stop\n");
return 0;
}
static int
axxia_i2c_xfer(struct i2c_adapter *adap, struct i2c_msg msgs[], int num)
{
struct axxia_i2c_dev *idev = i2c_get_adapdata(adap);
int i;
int ret = 0;
for (i = 0; ret == 0 && i < num; ++i)
ret = axxia_i2c_xfer_msg(idev, &msgs[i]);
axxia_i2c_stop(idev);
return ret ? : i;
}
static u32 axxia_i2c_func(struct i2c_adapter *adap)
{
u32 caps = (I2C_FUNC_I2C | I2C_FUNC_10BIT_ADDR |
I2C_FUNC_SMBUS_EMUL | I2C_FUNC_SMBUS_BLOCK_DATA);
return caps;
}
static const struct i2c_algorithm axxia_i2c_algo = {
.master_xfer = axxia_i2c_xfer,
.functionality = axxia_i2c_func,
};
static int axxia_i2c_probe(struct platform_device *pdev)
{
struct device_node *np = pdev->dev.of_node;
struct axxia_i2c_dev *idev = NULL;
struct resource *res;
void __iomem *base;
int irq;
int ret = 0;
idev = devm_kzalloc(&pdev->dev, sizeof(*idev), GFP_KERNEL);
if (!idev)
return -ENOMEM;
res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
base = devm_ioremap_resource(&pdev->dev, res);
if (IS_ERR(base))
return PTR_ERR(base);
irq = platform_get_irq(pdev, 0);
if (irq < 0) {
dev_err(&pdev->dev, "missing interrupt resource\n");
return irq;
}
idev->i2c_clk = devm_clk_get(&pdev->dev, "i2c");
if (IS_ERR(idev->i2c_clk)) {
dev_err(&pdev->dev, "missing clock\n");
return PTR_ERR(idev->i2c_clk);
}
idev->base = base;
idev->dev = &pdev->dev;
init_completion(&idev->msg_complete);
of_property_read_u32(np, "clock-frequency", &idev->bus_clk_rate);
if (idev->bus_clk_rate == 0)
idev->bus_clk_rate = 100000; /* default clock rate */
ret = axxia_i2c_init(idev);
if (ret) {
dev_err(&pdev->dev, "failed to initialize\n");
return ret;
}
ret = devm_request_irq(&pdev->dev, irq, axxia_i2c_isr, 0,
pdev->name, idev);
if (ret) {
dev_err(&pdev->dev, "failed to claim IRQ%d\n", irq);
return ret;
}
clk_prepare_enable(idev->i2c_clk);
i2c_set_adapdata(&idev->adapter, idev);
strlcpy(idev->adapter.name, pdev->name, sizeof(idev->adapter.name));
idev->adapter.owner = THIS_MODULE;
idev->adapter.algo = &axxia_i2c_algo;
idev->adapter.dev.parent = &pdev->dev;
idev->adapter.dev.of_node = pdev->dev.of_node;
platform_set_drvdata(pdev, idev);
ret = i2c_add_adapter(&idev->adapter);
if (ret) {
dev_err(&pdev->dev, "failed to add adapter\n");
return ret;
}
return 0;
}
static int axxia_i2c_remove(struct platform_device *pdev)
{
struct axxia_i2c_dev *idev = platform_get_drvdata(pdev);
clk_disable_unprepare(idev->i2c_clk);
i2c_del_adapter(&idev->adapter);
return 0;
}
/* Match table for of_platform binding */
static const struct of_device_id axxia_i2c_of_match[] = {
{ .compatible = "lsi,api2c", },
{},
};
MODULE_DEVICE_TABLE(of, axxia_i2c_of_match);
static struct platform_driver axxia_i2c_driver = {
.probe = axxia_i2c_probe,
.remove = axxia_i2c_remove,
.driver = {
.name = "axxia-i2c",
.of_match_table = axxia_i2c_of_match,
},
};
module_platform_driver(axxia_i2c_driver);
MODULE_DESCRIPTION("Axxia I2C Bus driver");
MODULE_AUTHOR("Anders Berg <anders.berg@lsi.com>");
MODULE_LICENSE("GPL v2");

View File

@ -96,7 +96,7 @@ static int ec_i2c_construct_message(u8 *buf, const struct i2c_msg i2c_msgs[],
msg->addr_flags = i2c_msg->addr;
if (i2c_msg->flags & I2C_M_TEN)
msg->addr_flags |= EC_I2C_FLAG_10BIT;
return -EINVAL;
if (i2c_msg->flags & I2C_M_RD) {
msg->addr_flags |= EC_I2C_FLAG_READ;
@ -220,7 +220,9 @@ static int ec_i2c_xfer(struct i2c_adapter *adap, struct i2c_msg i2c_msgs[],
}
}
ec_i2c_construct_message(request, i2c_msgs, num, bus_num);
result = ec_i2c_construct_message(request, i2c_msgs, num, bus_num);
if (result)
goto exit;
msg.version = 0;
msg.command = EC_CMD_I2C_PASSTHRU;
@ -313,11 +315,20 @@ static int ec_i2c_remove(struct platform_device *dev)
return 0;
}
#ifdef CONFIG_OF
static const struct of_device_id cros_ec_i2c_of_match[] = {
{ .compatible = "google,cros-ec-i2c-tunnel" },
{},
};
MODULE_DEVICE_TABLE(of, cros_ec_i2c_of_match);
#endif
static struct platform_driver ec_i2c_tunnel_driver = {
.probe = ec_i2c_probe,
.remove = ec_i2c_remove,
.driver = {
.name = "cros-ec-i2c-tunnel",
.of_match_table = of_match_ptr(cros_ec_i2c_of_match),
},
};

View File

@ -30,6 +30,7 @@
#include <linux/delay.h>
#include <linux/i2c.h>
#include <linux/clk.h>
#include <linux/clk-provider.h>
#include <linux/errno.h>
#include <linux/sched.h>
#include <linux/err.h>
@ -41,6 +42,7 @@
#include <linux/io.h>
#include <linux/slab.h>
#include <linux/acpi.h>
#include <linux/platform_data/i2c-designware.h>
#include "i2c-designware-core.h"
static struct i2c_algorithm i2c_dw_algo = {
@ -79,10 +81,7 @@ static void dw_i2c_acpi_params(struct platform_device *pdev, char method[],
static int dw_i2c_acpi_configure(struct platform_device *pdev)
{
struct dw_i2c_dev *dev = platform_get_drvdata(pdev);
bool fs_mode = dev->master_cfg & DW_IC_CON_SPEED_FAST;
if (!ACPI_HANDLE(&pdev->dev))
return -ENODEV;
const struct acpi_device_id *id;
dev->adapter.nr = -1;
dev->tx_fifo_depth = 32;
@ -92,14 +91,33 @@ static int dw_i2c_acpi_configure(struct platform_device *pdev)
* Try to get SDA hold time and *CNT values from an ACPI method if
* it exists for both supported speed modes.
*/
dw_i2c_acpi_params(pdev, "SSCN", &dev->ss_hcnt, &dev->ss_lcnt,
fs_mode ? NULL : &dev->sda_hold_time);
dw_i2c_acpi_params(pdev, "SSCN", &dev->ss_hcnt, &dev->ss_lcnt, NULL);
dw_i2c_acpi_params(pdev, "FMCN", &dev->fs_hcnt, &dev->fs_lcnt,
fs_mode ? &dev->sda_hold_time : NULL);
&dev->sda_hold_time);
/*
* Provide a way for Designware I2C host controllers that are not
* based on Intel LPSS to specify their input clock frequency via
* id->driver_data.
*/
id = acpi_match_device(pdev->dev.driver->acpi_match_table, &pdev->dev);
if (id && id->driver_data)
clk_register_fixed_rate(&pdev->dev, dev_name(&pdev->dev), NULL,
CLK_IS_ROOT, id->driver_data);
return 0;
}
static void dw_i2c_acpi_unconfigure(struct platform_device *pdev)
{
struct dw_i2c_dev *dev = platform_get_drvdata(pdev);
const struct acpi_device_id *id;
id = acpi_match_device(pdev->dev.driver->acpi_match_table, &pdev->dev);
if (id && id->driver_data)
clk_unregister(dev->clk);
}
static const struct acpi_device_id dw_i2c_acpi_match[] = {
{ "INT33C2", 0 },
{ "INT33C3", 0 },
@ -107,6 +125,7 @@ static const struct acpi_device_id dw_i2c_acpi_match[] = {
{ "INT3433", 0 },
{ "80860F41", 0 },
{ "808622C1", 0 },
{ "AMD0010", 133 * 1000 * 1000 },
{ }
};
MODULE_DEVICE_TABLE(acpi, dw_i2c_acpi_match);
@ -115,6 +134,7 @@ static inline int dw_i2c_acpi_configure(struct platform_device *pdev)
{
return -ENODEV;
}
static inline void dw_i2c_acpi_unconfigure(struct platform_device *pdev) { }
#endif
static int dw_i2c_probe(struct platform_device *pdev)
@ -122,7 +142,9 @@ static int dw_i2c_probe(struct platform_device *pdev)
struct dw_i2c_dev *dev;
struct i2c_adapter *adap;
struct resource *mem;
struct dw_i2c_platform_data *pdata;
int irq, r;
u32 clk_freq, ht = 0;
irq = platform_get_irq(pdev, 0);
if (irq < 0) {
@ -145,21 +167,14 @@ static int dw_i2c_probe(struct platform_device *pdev)
dev->irq = irq;
platform_set_drvdata(pdev, dev);
dev->clk = devm_clk_get(&pdev->dev, NULL);
dev->get_clk_rate_khz = i2c_dw_get_clk_rate_khz;
if (IS_ERR(dev->clk))
return PTR_ERR(dev->clk);
clk_prepare_enable(dev->clk);
if (pdev->dev.of_node) {
u32 ht = 0;
u32 ic_clk = dev->get_clk_rate_khz(dev);
/* fast mode by default because of legacy reasons */
clk_freq = 400000;
if (ACPI_COMPANION(&pdev->dev)) {
dw_i2c_acpi_configure(pdev);
} else if (pdev->dev.of_node) {
of_property_read_u32(pdev->dev.of_node,
"i2c-sda-hold-time-ns", &ht);
dev->sda_hold_time = div_u64((u64)ic_clk * ht + 500000,
1000000);
of_property_read_u32(pdev->dev.of_node,
"i2c-sda-falling-time-ns",
@ -167,6 +182,21 @@ static int dw_i2c_probe(struct platform_device *pdev)
of_property_read_u32(pdev->dev.of_node,
"i2c-scl-falling-time-ns",
&dev->scl_falling_time);
of_property_read_u32(pdev->dev.of_node, "clock-frequency",
&clk_freq);
/* Only standard mode at 100kHz and fast mode at 400kHz
* are supported.
*/
if (clk_freq != 100000 && clk_freq != 400000) {
dev_err(&pdev->dev, "Only 100kHz and 400kHz supported");
return -EINVAL;
}
} else {
pdata = dev_get_platdata(&pdev->dev);
if (pdata)
clk_freq = pdata->i2c_scl_freq;
}
dev->functionality =
@ -176,12 +206,27 @@ static int dw_i2c_probe(struct platform_device *pdev)
I2C_FUNC_SMBUS_BYTE_DATA |
I2C_FUNC_SMBUS_WORD_DATA |
I2C_FUNC_SMBUS_I2C_BLOCK;
dev->master_cfg = DW_IC_CON_MASTER | DW_IC_CON_SLAVE_DISABLE |
DW_IC_CON_RESTART_EN | DW_IC_CON_SPEED_FAST;
if (clk_freq == 100000)
dev->master_cfg = DW_IC_CON_MASTER | DW_IC_CON_SLAVE_DISABLE |
DW_IC_CON_RESTART_EN | DW_IC_CON_SPEED_STD;
else
dev->master_cfg = DW_IC_CON_MASTER | DW_IC_CON_SLAVE_DISABLE |
DW_IC_CON_RESTART_EN | DW_IC_CON_SPEED_FAST;
/* Try first if we can configure the device from ACPI */
r = dw_i2c_acpi_configure(pdev);
if (r) {
dev->clk = devm_clk_get(&pdev->dev, NULL);
dev->get_clk_rate_khz = i2c_dw_get_clk_rate_khz;
if (IS_ERR(dev->clk))
return PTR_ERR(dev->clk);
clk_prepare_enable(dev->clk);
if (!dev->sda_hold_time && ht) {
u32 ic_clk = dev->get_clk_rate_khz(dev);
dev->sda_hold_time = div_u64((u64)ic_clk * ht + 500000,
1000000);
}
if (!dev->tx_fifo_depth) {
u32 param1 = i2c_dw_read_comp_param(dev);
dev->tx_fifo_depth = ((param1 >> 16) & 0xff) + 1;
@ -237,6 +282,9 @@ static int dw_i2c_remove(struct platform_device *pdev)
pm_runtime_put(&pdev->dev);
pm_runtime_disable(&pdev->dev);
if (ACPI_COMPANION(&pdev->dev))
dw_i2c_acpi_unconfigure(pdev);
return 0;
}

View File

@ -83,7 +83,6 @@
#define HSI2C_INT_TX_ALMOSTEMPTY_EN (1u << 0)
#define HSI2C_INT_RX_ALMOSTFULL_EN (1u << 1)
#define HSI2C_INT_TRAILING_EN (1u << 6)
#define HSI2C_INT_I2C_EN (1u << 9)
/* I2C_INT_STAT Register bits */
#define HSI2C_INT_TX_ALMOSTEMPTY (1u << 0)
@ -95,6 +94,17 @@
#define HSI2C_INT_TRAILING (1u << 6)
#define HSI2C_INT_I2C (1u << 9)
#define HSI2C_INT_TRANS_DONE (1u << 7)
#define HSI2C_INT_TRANS_ABORT (1u << 8)
#define HSI2C_INT_NO_DEV_ACK (1u << 9)
#define HSI2C_INT_NO_DEV (1u << 10)
#define HSI2C_INT_TIMEOUT (1u << 11)
#define HSI2C_INT_I2C_TRANS (HSI2C_INT_TRANS_DONE | \
HSI2C_INT_TRANS_ABORT | \
HSI2C_INT_NO_DEV_ACK | \
HSI2C_INT_NO_DEV | \
HSI2C_INT_TIMEOUT)
/* I2C_FIFO_STAT Register bits */
#define HSI2C_RX_FIFO_EMPTY (1u << 24)
#define HSI2C_RX_FIFO_FULL (1u << 23)
@ -143,6 +153,8 @@
#define EXYNOS5_I2C_TIMEOUT (msecs_to_jiffies(1000))
#define HSI2C_EXYNOS7 BIT(0)
struct exynos5_i2c {
struct i2c_adapter adap;
unsigned int suspended:1;
@ -192,6 +204,7 @@ struct exynos5_i2c {
*/
struct exynos_hsi2c_variant {
unsigned int fifo_depth;
unsigned int hw;
};
static const struct exynos_hsi2c_variant exynos5250_hsi2c_data = {
@ -202,6 +215,11 @@ static const struct exynos_hsi2c_variant exynos5260_hsi2c_data = {
.fifo_depth = 16,
};
static const struct exynos_hsi2c_variant exynos7_hsi2c_data = {
.fifo_depth = 16,
.hw = HSI2C_EXYNOS7,
};
static const struct of_device_id exynos5_i2c_match[] = {
{
.compatible = "samsung,exynos5-hsi2c",
@ -212,6 +230,9 @@ static const struct of_device_id exynos5_i2c_match[] = {
}, {
.compatible = "samsung,exynos5260-hsi2c",
.data = &exynos5260_hsi2c_data
}, {
.compatible = "samsung,exynos7-hsi2c",
.data = &exynos7_hsi2c_data
}, {},
};
MODULE_DEVICE_TABLE(of, exynos5_i2c_match);
@ -256,13 +277,24 @@ static int exynos5_i2c_set_timing(struct exynos5_i2c *i2c, int mode)
i2c->hs_clock : i2c->fs_clock;
/*
* In case of HSI2C controller in Exynos5 series
* FPCLK / FI2C =
* (CLK_DIV + 1) * (TSCLK_L + TSCLK_H + 2) + 8 + 2 * FLT_CYCLE
*
* In case of HSI2C controllers in Exynos7 series
* FPCLK / FI2C =
* (CLK_DIV + 1) * (TSCLK_L + TSCLK_H + 2) + 8 + FLT_CYCLE
*
* utemp0 = (CLK_DIV + 1) * (TSCLK_L + TSCLK_H + 2)
* utemp1 = (TSCLK_L + TSCLK_H + 2)
*/
t_ftl_cycle = (readl(i2c->regs + HSI2C_CONF) >> 16) & 0x7;
utemp0 = (clkin / op_clk) - 8 - 2 * t_ftl_cycle;
utemp0 = (clkin / op_clk) - 8;
if (i2c->variant->hw == HSI2C_EXYNOS7)
utemp0 -= t_ftl_cycle;
else
utemp0 -= 2 * t_ftl_cycle;
/* CLK_DIV max is 256 */
for (div = 0; div < 256; div++) {
@ -407,7 +439,28 @@ static irqreturn_t exynos5_i2c_irq(int irqno, void *dev_id)
writel(int_status, i2c->regs + HSI2C_INT_STATUS);
/* handle interrupt related to the transfer status */
if (int_status & HSI2C_INT_I2C) {
if (i2c->variant->hw == HSI2C_EXYNOS7) {
if (int_status & HSI2C_INT_TRANS_DONE) {
i2c->trans_done = 1;
i2c->state = 0;
} else if (int_status & HSI2C_INT_TRANS_ABORT) {
dev_dbg(i2c->dev, "Deal with arbitration lose\n");
i2c->state = -EAGAIN;
goto stop;
} else if (int_status & HSI2C_INT_NO_DEV_ACK) {
dev_dbg(i2c->dev, "No ACK from device\n");
i2c->state = -ENXIO;
goto stop;
} else if (int_status & HSI2C_INT_NO_DEV) {
dev_dbg(i2c->dev, "No device\n");
i2c->state = -ENXIO;
goto stop;
} else if (int_status & HSI2C_INT_TIMEOUT) {
dev_dbg(i2c->dev, "Accessing device timed out\n");
i2c->state = -EAGAIN;
goto stop;
}
} else if (int_status & HSI2C_INT_I2C) {
trans_status = readl(i2c->regs + HSI2C_TRANS_STATUS);
if (trans_status & HSI2C_NO_DEV_ACK) {
dev_dbg(i2c->dev, "No ACK from device\n");
@ -512,12 +565,17 @@ static int exynos5_i2c_wait_bus_idle(struct exynos5_i2c *i2c)
static void exynos5_i2c_message_start(struct exynos5_i2c *i2c, int stop)
{
u32 i2c_ctl;
u32 int_en = HSI2C_INT_I2C_EN;
u32 int_en = 0;
u32 i2c_auto_conf = 0;
u32 fifo_ctl;
unsigned long flags;
unsigned short trig_lvl;
if (i2c->variant->hw == HSI2C_EXYNOS7)
int_en |= HSI2C_INT_I2C_TRANS;
else
int_en |= HSI2C_INT_I2C;
i2c_ctl = readl(i2c->regs + HSI2C_CTL);
i2c_ctl &= ~(HSI2C_TXCHON | HSI2C_RXCHON);
fifo_ctl = HSI2C_RXFIFO_EN | HSI2C_TXFIFO_EN;
@ -724,12 +782,13 @@ static int exynos5_i2c_probe(struct platform_device *pdev)
goto err_clk;
}
/* Need to check the variant before setting up. */
i2c->variant = exynos5_i2c_get_variant(pdev);
ret = exynos5_hsi2c_clock_setup(i2c);
if (ret)
goto err_clk;
i2c->variant = exynos5_i2c_get_variant(pdev);
exynos5_i2c_reset(i2c);
ret = i2c_add_adapter(&i2c->adap);

View File

@ -0,0 +1,557 @@
/*
* Copyright (c) 2014 Linaro Ltd.
* Copyright (c) 2014 Hisilicon Limited.
*
* 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.
*
* Now only support 7 bit address.
*/
#include <linux/clk.h>
#include <linux/delay.h>
#include <linux/i2c.h>
#include <linux/io.h>
#include <linux/interrupt.h>
#include <linux/module.h>
#include <linux/of.h>
#include <linux/platform_device.h>
#include <linux/pm_runtime.h>
/* Register Map */
#define HIX5I2C_CTRL 0x00
#define HIX5I2C_COM 0x04
#define HIX5I2C_ICR 0x08
#define HIX5I2C_SR 0x0c
#define HIX5I2C_SCL_H 0x10
#define HIX5I2C_SCL_L 0x14
#define HIX5I2C_TXR 0x18
#define HIX5I2C_RXR 0x1c
/* I2C_CTRL_REG */
#define I2C_ENABLE BIT(8)
#define I2C_UNMASK_TOTAL BIT(7)
#define I2C_UNMASK_START BIT(6)
#define I2C_UNMASK_END BIT(5)
#define I2C_UNMASK_SEND BIT(4)
#define I2C_UNMASK_RECEIVE BIT(3)
#define I2C_UNMASK_ACK BIT(2)
#define I2C_UNMASK_ARBITRATE BIT(1)
#define I2C_UNMASK_OVER BIT(0)
#define I2C_UNMASK_ALL (I2C_UNMASK_ACK | I2C_UNMASK_OVER)
/* I2C_COM_REG */
#define I2C_NO_ACK BIT(4)
#define I2C_START BIT(3)
#define I2C_READ BIT(2)
#define I2C_WRITE BIT(1)
#define I2C_STOP BIT(0)
/* I2C_ICR_REG */
#define I2C_CLEAR_START BIT(6)
#define I2C_CLEAR_END BIT(5)
#define I2C_CLEAR_SEND BIT(4)
#define I2C_CLEAR_RECEIVE BIT(3)
#define I2C_CLEAR_ACK BIT(2)
#define I2C_CLEAR_ARBITRATE BIT(1)
#define I2C_CLEAR_OVER BIT(0)
#define I2C_CLEAR_ALL (I2C_CLEAR_START | I2C_CLEAR_END | \
I2C_CLEAR_SEND | I2C_CLEAR_RECEIVE | \
I2C_CLEAR_ACK | I2C_CLEAR_ARBITRATE | \
I2C_CLEAR_OVER)
/* I2C_SR_REG */
#define I2C_BUSY BIT(7)
#define I2C_START_INTR BIT(6)
#define I2C_END_INTR BIT(5)
#define I2C_SEND_INTR BIT(4)
#define I2C_RECEIVE_INTR BIT(3)
#define I2C_ACK_INTR BIT(2)
#define I2C_ARBITRATE_INTR BIT(1)
#define I2C_OVER_INTR BIT(0)
#define HIX5I2C_MAX_FREQ 400000 /* 400k */
#define HIX5I2C_READ_OPERATION 0x01
enum hix5hd2_i2c_state {
HIX5I2C_STAT_RW_ERR = -1,
HIX5I2C_STAT_INIT,
HIX5I2C_STAT_RW,
HIX5I2C_STAT_SND_STOP,
HIX5I2C_STAT_RW_SUCCESS,
};
struct hix5hd2_i2c_priv {
struct i2c_adapter adap;
struct i2c_msg *msg;
struct completion msg_complete;
unsigned int msg_idx;
unsigned int msg_len;
int stop;
void __iomem *regs;
struct clk *clk;
struct device *dev;
spinlock_t lock; /* IRQ synchronization */
int err;
unsigned int freq;
enum hix5hd2_i2c_state state;
};
static u32 hix5hd2_i2c_clr_pend_irq(struct hix5hd2_i2c_priv *priv)
{
u32 val = readl_relaxed(priv->regs + HIX5I2C_SR);
writel_relaxed(val, priv->regs + HIX5I2C_ICR);
return val;
}
static void hix5hd2_i2c_clr_all_irq(struct hix5hd2_i2c_priv *priv)
{
writel_relaxed(I2C_CLEAR_ALL, priv->regs + HIX5I2C_ICR);
}
static void hix5hd2_i2c_disable_irq(struct hix5hd2_i2c_priv *priv)
{
writel_relaxed(0, priv->regs + HIX5I2C_CTRL);
}
static void hix5hd2_i2c_enable_irq(struct hix5hd2_i2c_priv *priv)
{
writel_relaxed(I2C_ENABLE | I2C_UNMASK_TOTAL | I2C_UNMASK_ALL,
priv->regs + HIX5I2C_CTRL);
}
static void hix5hd2_i2c_drv_setrate(struct hix5hd2_i2c_priv *priv)
{
u32 rate, val;
u32 scl, sysclock;
/* close all i2c interrupt */
val = readl_relaxed(priv->regs + HIX5I2C_CTRL);
writel_relaxed(val & (~I2C_UNMASK_TOTAL), priv->regs + HIX5I2C_CTRL);
rate = priv->freq;
sysclock = clk_get_rate(priv->clk);
scl = (sysclock / (rate * 2)) / 2 - 1;
writel_relaxed(scl, priv->regs + HIX5I2C_SCL_H);
writel_relaxed(scl, priv->regs + HIX5I2C_SCL_L);
/* restore original interrupt*/
writel_relaxed(val, priv->regs + HIX5I2C_CTRL);
dev_dbg(priv->dev, "%s: sysclock=%d, rate=%d, scl=%d\n",
__func__, sysclock, rate, scl);
}
static void hix5hd2_i2c_init(struct hix5hd2_i2c_priv *priv)
{
hix5hd2_i2c_disable_irq(priv);
hix5hd2_i2c_drv_setrate(priv);
hix5hd2_i2c_clr_all_irq(priv);
hix5hd2_i2c_enable_irq(priv);
}
static void hix5hd2_i2c_reset(struct hix5hd2_i2c_priv *priv)
{
clk_disable_unprepare(priv->clk);
msleep(20);
clk_prepare_enable(priv->clk);
hix5hd2_i2c_init(priv);
}
static int hix5hd2_i2c_wait_bus_idle(struct hix5hd2_i2c_priv *priv)
{
unsigned long stop_time;
u32 int_status;
/* wait for 100 milli seconds for the bus to be idle */
stop_time = jiffies + msecs_to_jiffies(100);
do {
int_status = hix5hd2_i2c_clr_pend_irq(priv);
if (!(int_status & I2C_BUSY))
return 0;
usleep_range(50, 200);
} while (time_before(jiffies, stop_time));
return -EBUSY;
}
static void hix5hd2_rw_over(struct hix5hd2_i2c_priv *priv)
{
if (priv->state == HIX5I2C_STAT_SND_STOP)
dev_dbg(priv->dev, "%s: rw and send stop over\n", __func__);
else
dev_dbg(priv->dev, "%s: have not data to send\n", __func__);
priv->state = HIX5I2C_STAT_RW_SUCCESS;
priv->err = 0;
}
static void hix5hd2_rw_handle_stop(struct hix5hd2_i2c_priv *priv)
{
if (priv->stop) {
priv->state = HIX5I2C_STAT_SND_STOP;
writel_relaxed(I2C_STOP, priv->regs + HIX5I2C_COM);
} else {
hix5hd2_rw_over(priv);
}
}
static void hix5hd2_read_handle(struct hix5hd2_i2c_priv *priv)
{
if (priv->msg_len == 1) {
/* the last byte don't need send ACK */
writel_relaxed(I2C_READ | I2C_NO_ACK, priv->regs + HIX5I2C_COM);
} else if (priv->msg_len > 1) {
/* if i2c master receive data will send ACK */
writel_relaxed(I2C_READ, priv->regs + HIX5I2C_COM);
} else {
hix5hd2_rw_handle_stop(priv);
}
}
static void hix5hd2_write_handle(struct hix5hd2_i2c_priv *priv)
{
u8 data;
if (priv->msg_len > 0) {
data = priv->msg->buf[priv->msg_idx++];
writel_relaxed(data, priv->regs + HIX5I2C_TXR);
writel_relaxed(I2C_WRITE, priv->regs + HIX5I2C_COM);
} else {
hix5hd2_rw_handle_stop(priv);
}
}
static int hix5hd2_rw_preprocess(struct hix5hd2_i2c_priv *priv)
{
u8 data;
if (priv->state == HIX5I2C_STAT_INIT) {
priv->state = HIX5I2C_STAT_RW;
} else if (priv->state == HIX5I2C_STAT_RW) {
if (priv->msg->flags & I2C_M_RD) {
data = readl_relaxed(priv->regs + HIX5I2C_RXR);
priv->msg->buf[priv->msg_idx++] = data;
}
priv->msg_len--;
} else {
dev_dbg(priv->dev, "%s: error: priv->state = %d, msg_len = %d\n",
__func__, priv->state, priv->msg_len);
return -EAGAIN;
}
return 0;
}
static irqreturn_t hix5hd2_i2c_irq(int irqno, void *dev_id)
{
struct hix5hd2_i2c_priv *priv = dev_id;
u32 int_status;
int ret;
spin_lock(&priv->lock);
int_status = hix5hd2_i2c_clr_pend_irq(priv);
/* handle error */
if (int_status & I2C_ARBITRATE_INTR) {
/* bus error */
dev_dbg(priv->dev, "ARB bus loss\n");
priv->err = -EAGAIN;
priv->state = HIX5I2C_STAT_RW_ERR;
goto stop;
} else if (int_status & I2C_ACK_INTR) {
/* ack error */
dev_dbg(priv->dev, "No ACK from device\n");
priv->err = -ENXIO;
priv->state = HIX5I2C_STAT_RW_ERR;
goto stop;
}
if (int_status & I2C_OVER_INTR) {
if (priv->msg_len > 0) {
ret = hix5hd2_rw_preprocess(priv);
if (ret) {
priv->err = ret;
priv->state = HIX5I2C_STAT_RW_ERR;
goto stop;
}
if (priv->msg->flags & I2C_M_RD)
hix5hd2_read_handle(priv);
else
hix5hd2_write_handle(priv);
} else {
hix5hd2_rw_over(priv);
}
}
stop:
if ((priv->state == HIX5I2C_STAT_RW_SUCCESS &&
priv->msg->len == priv->msg_idx) ||
(priv->state == HIX5I2C_STAT_RW_ERR)) {
hix5hd2_i2c_disable_irq(priv);
hix5hd2_i2c_clr_pend_irq(priv);
complete(&priv->msg_complete);
}
spin_unlock(&priv->lock);
return IRQ_HANDLED;
}
static void hix5hd2_i2c_message_start(struct hix5hd2_i2c_priv *priv, int stop)
{
unsigned long flags;
spin_lock_irqsave(&priv->lock, flags);
hix5hd2_i2c_clr_all_irq(priv);
hix5hd2_i2c_enable_irq(priv);
if (priv->msg->flags & I2C_M_RD)
writel_relaxed((priv->msg->addr << 1) | HIX5I2C_READ_OPERATION,
priv->regs + HIX5I2C_TXR);
else
writel_relaxed(priv->msg->addr << 1,
priv->regs + HIX5I2C_TXR);
writel_relaxed(I2C_WRITE | I2C_START, priv->regs + HIX5I2C_COM);
spin_unlock_irqrestore(&priv->lock, flags);
}
static int hix5hd2_i2c_xfer_msg(struct hix5hd2_i2c_priv *priv,
struct i2c_msg *msgs, int stop)
{
unsigned long timeout;
int ret;
priv->msg = msgs;
priv->msg_idx = 0;
priv->msg_len = priv->msg->len;
priv->stop = stop;
priv->err = 0;
priv->state = HIX5I2C_STAT_INIT;
reinit_completion(&priv->msg_complete);
hix5hd2_i2c_message_start(priv, stop);
timeout = wait_for_completion_timeout(&priv->msg_complete,
priv->adap.timeout);
if (timeout == 0) {
priv->state = HIX5I2C_STAT_RW_ERR;
priv->err = -ETIMEDOUT;
dev_warn(priv->dev, "%s timeout=%d\n",
msgs->flags & I2C_M_RD ? "rx" : "tx",
priv->adap.timeout);
}
ret = priv->state;
/*
* If this is the last message to be transfered (stop == 1)
* Then check if the bus can be brought back to idle.
*/
if (priv->state == HIX5I2C_STAT_RW_SUCCESS && stop)
ret = hix5hd2_i2c_wait_bus_idle(priv);
if (ret < 0)
hix5hd2_i2c_reset(priv);
return priv->err;
}
static int hix5hd2_i2c_xfer(struct i2c_adapter *adap,
struct i2c_msg *msgs, int num)
{
struct hix5hd2_i2c_priv *priv = i2c_get_adapdata(adap);
int i, ret, stop;
pm_runtime_get_sync(priv->dev);
for (i = 0; i < num; i++, msgs++) {
stop = (i == num - 1);
ret = hix5hd2_i2c_xfer_msg(priv, msgs, stop);
if (ret < 0)
goto out;
}
if (i == num) {
ret = num;
} else {
/* Only one message, cannot access the device */
if (i == 1)
ret = -EREMOTEIO;
else
ret = i;
dev_warn(priv->dev, "xfer message failed\n");
}
out:
pm_runtime_mark_last_busy(priv->dev);
pm_runtime_put_autosuspend(priv->dev);
return ret;
}
static u32 hix5hd2_i2c_func(struct i2c_adapter *adap)
{
return I2C_FUNC_I2C | (I2C_FUNC_SMBUS_EMUL & ~I2C_FUNC_SMBUS_QUICK);
}
static const struct i2c_algorithm hix5hd2_i2c_algorithm = {
.master_xfer = hix5hd2_i2c_xfer,
.functionality = hix5hd2_i2c_func,
};
static int hix5hd2_i2c_probe(struct platform_device *pdev)
{
struct device_node *np = pdev->dev.of_node;
struct hix5hd2_i2c_priv *priv;
struct resource *mem;
unsigned int freq;
int irq, ret;
priv = devm_kzalloc(&pdev->dev, sizeof(*priv), GFP_KERNEL);
if (!priv)
return -ENOMEM;
if (of_property_read_u32(np, "clock-frequency", &freq)) {
/* use 100k as default value */
priv->freq = 100000;
} else {
if (freq > HIX5I2C_MAX_FREQ) {
priv->freq = HIX5I2C_MAX_FREQ;
dev_warn(priv->dev, "use max freq %d instead\n",
HIX5I2C_MAX_FREQ);
} else {
priv->freq = freq;
}
}
mem = platform_get_resource(pdev, IORESOURCE_MEM, 0);
priv->regs = devm_ioremap_resource(&pdev->dev, mem);
if (IS_ERR(priv->regs))
return PTR_ERR(priv->regs);
irq = platform_get_irq(pdev, 0);
if (irq <= 0) {
dev_err(&pdev->dev, "cannot find HS-I2C IRQ\n");
return irq;
}
priv->clk = devm_clk_get(&pdev->dev, NULL);
if (IS_ERR(priv->clk)) {
dev_err(&pdev->dev, "cannot get clock\n");
return PTR_ERR(priv->clk);
}
clk_prepare_enable(priv->clk);
strlcpy(priv->adap.name, "hix5hd2-i2c", sizeof(priv->adap.name));
priv->dev = &pdev->dev;
priv->adap.owner = THIS_MODULE;
priv->adap.algo = &hix5hd2_i2c_algorithm;
priv->adap.retries = 3;
priv->adap.dev.of_node = np;
priv->adap.algo_data = priv;
priv->adap.dev.parent = &pdev->dev;
i2c_set_adapdata(&priv->adap, priv);
platform_set_drvdata(pdev, priv);
spin_lock_init(&priv->lock);
init_completion(&priv->msg_complete);
hix5hd2_i2c_init(priv);
ret = devm_request_irq(&pdev->dev, irq, hix5hd2_i2c_irq,
IRQF_NO_SUSPEND | IRQF_ONESHOT,
dev_name(&pdev->dev), priv);
if (ret != 0) {
dev_err(&pdev->dev, "cannot request HS-I2C IRQ %d\n", irq);
goto err_clk;
}
pm_suspend_ignore_children(&pdev->dev, true);
pm_runtime_set_autosuspend_delay(priv->dev, MSEC_PER_SEC);
pm_runtime_use_autosuspend(priv->dev);
pm_runtime_set_active(priv->dev);
pm_runtime_enable(priv->dev);
ret = i2c_add_adapter(&priv->adap);
if (ret < 0) {
dev_err(&pdev->dev, "failed to add bus to i2c core\n");
goto err_runtime;
}
return ret;
err_runtime:
pm_runtime_disable(priv->dev);
pm_runtime_set_suspended(priv->dev);
err_clk:
clk_disable_unprepare(priv->clk);
return ret;
}
static int hix5hd2_i2c_remove(struct platform_device *pdev)
{
struct hix5hd2_i2c_priv *priv = platform_get_drvdata(pdev);
i2c_del_adapter(&priv->adap);
pm_runtime_disable(priv->dev);
pm_runtime_set_suspended(priv->dev);
return 0;
}
#ifdef CONFIG_PM
static int hix5hd2_i2c_runtime_suspend(struct device *dev)
{
struct platform_device *pdev = to_platform_device(dev);
struct hix5hd2_i2c_priv *priv = platform_get_drvdata(pdev);
clk_disable_unprepare(priv->clk);
return 0;
}
static int hix5hd2_i2c_runtime_resume(struct device *dev)
{
struct platform_device *pdev = to_platform_device(dev);
struct hix5hd2_i2c_priv *priv = platform_get_drvdata(pdev);
clk_prepare_enable(priv->clk);
hix5hd2_i2c_init(priv);
return 0;
}
#endif
static const struct dev_pm_ops hix5hd2_i2c_pm_ops = {
SET_PM_RUNTIME_PM_OPS(hix5hd2_i2c_runtime_suspend,
hix5hd2_i2c_runtime_resume,
NULL)
};
static const struct of_device_id hix5hd2_i2c_match[] = {
{ .compatible = "hisilicon,hix5hd2-i2c" },
{},
};
MODULE_DEVICE_TABLE(of, hix5hd2_i2c_match);
static struct platform_driver hix5hd2_i2c_driver = {
.probe = hix5hd2_i2c_probe,
.remove = hix5hd2_i2c_remove,
.driver = {
.name = "hix5hd2-i2c",
.pm = &hix5hd2_i2c_pm_ops,
.of_match_table = hix5hd2_i2c_match,
},
};
module_platform_driver(hix5hd2_i2c_driver);
MODULE_DESCRIPTION("Hix5hd2 I2C Bus driver");
MODULE_AUTHOR("Wei Yan <sledge.yanwei@huawei.com>");
MODULE_LICENSE("GPL");
MODULE_ALIAS("platform:i2c-hix5hd2");

View File

@ -62,6 +62,7 @@
* Wildcat Point (PCH) 0x8ca2 32 hard yes yes yes
* Wildcat Point-LP (PCH) 0x9ca2 32 hard yes yes yes
* BayTrail (SOC) 0x0f12 32 hard yes yes yes
* Sunrise Point-H (PCH) 0xa123 32 hard yes yes yes
*
* Features supported by this driver:
* Software PEC no
@ -184,6 +185,7 @@
#define PCI_DEVICE_ID_INTEL_WELLSBURG_SMBUS_MS2 0x8d7f
#define PCI_DEVICE_ID_INTEL_LYNXPOINT_LP_SMBUS 0x9c22
#define PCI_DEVICE_ID_INTEL_WILDCATPOINT_LP_SMBUS 0x9ca2
#define PCI_DEVICE_ID_INTEL_SUNRISEPOINT_H_SMBUS 0xa123
struct i801_mux_config {
char *gpio_chip;
@ -830,6 +832,7 @@ static const struct pci_device_id i801_ids[] = {
{ PCI_DEVICE(PCI_VENDOR_ID_INTEL, PCI_DEVICE_ID_INTEL_WILDCATPOINT_LP_SMBUS) },
{ PCI_DEVICE(PCI_VENDOR_ID_INTEL, PCI_DEVICE_ID_INTEL_BAYTRAIL_SMBUS) },
{ PCI_DEVICE(PCI_VENDOR_ID_INTEL, PCI_DEVICE_ID_INTEL_BRASWELL_SMBUS) },
{ PCI_DEVICE(PCI_VENDOR_ID_INTEL, PCI_DEVICE_ID_INTEL_SUNRISEPOINT_H_SMBUS) },
{ 0, }
};

View File

@ -268,6 +268,14 @@ static int i2c_imx_bus_busy(struct imx_i2c_struct *i2c_imx, int for_busy)
while (1) {
temp = imx_i2c_read_reg(i2c_imx, IMX_I2C_I2SR);
/* check for arbitration lost */
if (temp & I2SR_IAL) {
temp &= ~I2SR_IAL;
imx_i2c_write_reg(temp, i2c_imx, IMX_I2C_I2SR);
return -EAGAIN;
}
if (for_busy && (temp & I2SR_IBB))
break;
if (!for_busy && !(temp & I2SR_IBB))
@ -702,7 +710,7 @@ static int i2c_imx_probe(struct platform_device *pdev)
pdev->name, i2c_imx);
if (ret) {
dev_err(&pdev->dev, "can't claim irq %d\n", irq);
return ret;
goto clk_disable;
}
/* Init queue */
@ -727,7 +735,7 @@ static int i2c_imx_probe(struct platform_device *pdev)
ret = i2c_add_numbered_adapter(&i2c_imx->adapter);
if (ret < 0) {
dev_err(&pdev->dev, "registration failed\n");
return ret;
goto clk_disable;
}
/* Set up platform driver data */
@ -741,6 +749,10 @@ static int i2c_imx_probe(struct platform_device *pdev)
dev_info(&i2c_imx->adapter.dev, "IMX I2C adapter registered\n");
return 0; /* Return OK */
clk_disable:
clk_disable_unprepare(i2c_imx->clk);
return ret;
}
static int i2c_imx_remove(struct platform_device *pdev)

View File

@ -81,7 +81,7 @@
#define PCI_DEVICE_ID_INTEL_S1200_SMT1 0x0c5a
#define PCI_DEVICE_ID_INTEL_AVOTON_SMT 0x1f15
#define ISMT_DESC_ENTRIES 32 /* number of descriptor entries */
#define ISMT_DESC_ENTRIES 2 /* number of descriptor entries */
#define ISMT_MAX_RETRIES 3 /* number of SMBus retries to attempt */
/* Hardware Descriptor Constants - Control Field */

View File

@ -307,6 +307,9 @@ static int mxs_i2c_pio_wait_xfer_end(struct mxs_i2c_dev *i2c)
unsigned long timeout = jiffies + msecs_to_jiffies(1000);
while (readl(i2c->regs + MXS_I2C_CTRL0) & MXS_I2C_CTRL0_RUN) {
if (readl(i2c->regs + MXS_I2C_CTRL1) &
MXS_I2C_CTRL1_NO_SLAVE_ACK_IRQ)
return -ENXIO;
if (time_after(jiffies, timeout))
return -ETIMEDOUT;
cond_resched();

View File

@ -195,7 +195,7 @@ static int rcar_i2c_clock_calculate(struct rcar_i2c_priv *priv,
*/
rate = clk_get_rate(priv->clk);
cdf = rate / 20000000;
if (cdf >= 1 << cdf_width) {
if (cdf >= 1U << cdf_width) {
dev_err(dev, "Input clock %lu too high\n", rate);
return -EIO;
}
@ -245,7 +245,7 @@ scgd_find:
return 0;
}
static int rcar_i2c_prepare_msg(struct rcar_i2c_priv *priv)
static void rcar_i2c_prepare_msg(struct rcar_i2c_priv *priv)
{
int read = !!rcar_i2c_is_recv(priv);
@ -253,8 +253,6 @@ static int rcar_i2c_prepare_msg(struct rcar_i2c_priv *priv)
rcar_i2c_write(priv, ICMSR, 0);
rcar_i2c_write(priv, ICMCR, RCAR_BUS_PHASE_START);
rcar_i2c_write(priv, ICMIER, read ? RCAR_IRQ_RECV : RCAR_IRQ_SEND);
return 0;
}
/*
@ -365,6 +363,7 @@ static int rcar_i2c_irq_recv(struct rcar_i2c_priv *priv, u32 msr)
static irqreturn_t rcar_i2c_irq(int irq, void *ptr)
{
struct rcar_i2c_priv *priv = ptr;
irqreturn_t result = IRQ_HANDLED;
u32 msr;
/*-------------- spin lock -----------------*/
@ -374,6 +373,10 @@ static irqreturn_t rcar_i2c_irq(int irq, void *ptr)
/* Only handle interrupts that are currently enabled */
msr &= rcar_i2c_read(priv, ICMIER);
if (!msr) {
result = IRQ_NONE;
goto exit;
}
/* Arbitration lost */
if (msr & MAL) {
@ -408,10 +411,11 @@ out:
wake_up(&priv->wait);
}
exit:
spin_unlock(&priv->lock);
/*-------------- spin unlock -----------------*/
return IRQ_HANDLED;
return result;
}
static int rcar_i2c_master_xfer(struct i2c_adapter *adap,
@ -453,17 +457,14 @@ static int rcar_i2c_master_xfer(struct i2c_adapter *adap,
priv->msg = &msgs[i];
priv->pos = 0;
priv->flags = 0;
if (priv->msg == &msgs[num - 1])
if (i == num - 1)
rcar_i2c_flags_set(priv, ID_LAST_MSG);
ret = rcar_i2c_prepare_msg(priv);
rcar_i2c_prepare_msg(priv);
spin_unlock_irqrestore(&priv->lock, flags);
/*-------------- spin unlock -----------------*/
if (ret < 0)
break;
timeout = wait_event_timeout(priv->wait,
rcar_i2c_flags_has(priv, ID_DONE),
5 * HZ);

View File

@ -208,7 +208,7 @@ static void rk3x_i2c_prepare_read(struct rk3x_i2c *i2c)
* The hw can read up to 32 bytes at a time. If we need more than one
* chunk, send an ACK after the last byte of the current chunk.
*/
if (unlikely(len > 32)) {
if (len > 32) {
len = 32;
con &= ~REG_CON_LASTACK;
} else {
@ -403,7 +403,7 @@ static irqreturn_t rk3x_i2c_irq(int irqno, void *dev_id)
}
/* is there anything left to handle? */
if (unlikely((ipd & REG_INT_ALL) == 0))
if ((ipd & REG_INT_ALL) == 0)
goto out;
switch (i2c->state) {

View File

@ -1928,9 +1928,6 @@ struct ec_response_power_info {
#define EC_CMD_I2C_PASSTHRU 0x9e
/* Slave address is 10 (not 7) bit */
#define EC_I2C_FLAG_10BIT (1 << 16)
/* Read data; if not present, message is a write */
#define EC_I2C_FLAG_READ (1 << 15)

View File

@ -0,0 +1,21 @@
/*
* Copyright(c) 2014 Intel Corporation.
*
* This program is free software; you can redistribute it and/or modify it
* under the terms and conditions of the GNU General Public License,
* version 2, as published by the Free Software Foundation.
*
* This program is distributed in the hope 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 I2C_DESIGNWARE_H
#define I2C_DESIGNWARE_H
struct dw_i2c_platform_data {
unsigned int i2c_scl_freq;
};
#endif