summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorDossym Nurmukhanov <dossym@google.com>2020-12-12 02:46:43 +0000
committerCommit Bot <commit-bot@chromium.org>2020-12-12 20:15:38 +0000
commit52863374ad592b80b24def9689856ecda2d645d0 (patch)
tree40dd4839b515c0e404405f23168be339bd5aa0ba
parentc03b3d8174231562369cd51f3fedf82e75655273 (diff)
downloadchrome-ec-52863374ad592b80b24def9689856ecda2d645d0.tar.gz
COIL: Standardize i2c peripheral language
BUG=none TEST=validate volteer build (i2c_peripheral.c is not used by any boards) BRANCH=none Signed-off-by: dossym@chromium.org Change-Id: Ib2d78dc3fc9f4f189f84409cf43ab96788c429be Reviewed-on: https://chromium-review.googlesource.com/c/chromiumos/platform/ec/+/2587227 Reviewed-by: Daisuke Nojiri <dnojiri@chromium.org>
-rw-r--r--chip/it83xx/i2c.c12
-rw-r--r--chip/it83xx/i2c_peripheral.c149
-rw-r--r--chip/it83xx/intc.c8
-rw-r--r--chip/it83xx/intc.h2
-rw-r--r--include/i2c_peripheral.h18
5 files changed, 94 insertions, 95 deletions
diff --git a/chip/it83xx/i2c.c b/chip/it83xx/i2c.c
index 2f1ef9e605..3fac0fbec5 100644
--- a/chip/it83xx/i2c.c
+++ b/chip/it83xx/i2c.c
@@ -94,7 +94,7 @@ enum enhanced_i2c_ctl {
E_RX_MODE = 0x80,
/* State reset and hardware reset */
E_STS_AND_HW_RST = (E_STS_RST | E_HW_RST),
- /* Generate start condition and transmit slave address */
+ /* Generate start condition and transmit peripheral address */
E_START_ID = (E_INT_EN | E_MODE_SEL | E_ACK | E_START | E_HW_RST),
/* Generate stop condition */
E_FINISH = (E_INT_EN | E_MODE_SEL | E_ACK | E_STOP | E_HW_RST),
@@ -284,7 +284,7 @@ static void i2c_pio_trans_data(int p, enum enhanced_i2c_transfer_direct direct,
p_ch = i2c_ch_reg_shift(p);
if (first_byte) {
- /* First byte must be slave address. */
+ /* First byte must be peripheral address. */
IT83XX_I2C_DTR(p_ch) =
data | (direct == RX_DIRECT ? BIT(0) : 0);
/* start or repeat start signal. */
@@ -317,7 +317,7 @@ static int i2c_tran_write(int p)
IT83XX_SMB_HOCTL2(p) = 0x13;
/*
* bit0, Direction of the host transfer.
- * bit[1:7}, Address of the targeted slave.
+ * bit[1:7}, Address of the targeted peripheral.
*/
IT83XX_SMB_TRASLA(p) = pd->addr_8bit;
/* Send first byte */
@@ -377,7 +377,7 @@ static int i2c_tran_read(int p)
IT83XX_SMB_HOCTL2(p) = 0x13;
/*
* bit0, Direction of the host transfer.
- * bit[1:7}, Address of the targeted slave.
+ * bit[1:7}, Address of the targeted peripheral.
*/
IT83XX_SMB_TRASLA(p) = pd->addr_8bit | 0x01;
/* clear start flag */
@@ -641,7 +641,7 @@ int i2c_is_busy(int port)
return (IT83XX_I2C_STR(p_ch) & E_HOSTA_BB);
}
-int chip_i2c_xfer(int port, uint16_t slave_addr_flags,
+int chip_i2c_xfer(int port, uint16_t addr_flags,
const uint8_t *out, int out_size,
uint8_t *in, int in_size, int flags)
{
@@ -665,7 +665,7 @@ int chip_i2c_xfer(int port, uint16_t slave_addr_flags,
pd->widx = 0;
pd->ridx = 0;
pd->err = 0;
- pd->addr_8bit = I2C_STRIP_FLAGS(slave_addr_flags) << 1;
+ pd->addr_8bit = I2C_STRIP_FLAGS(addr_flags) << 1;
/* Make sure we're in a good state to start */
if ((flags & I2C_XFER_START) && (i2c_is_busy(port)
diff --git a/chip/it83xx/i2c_peripheral.c b/chip/it83xx/i2c_peripheral.c
index 63cf56a4d9..91eb2c1dfb 100644
--- a/chip/it83xx/i2c_peripheral.c
+++ b/chip/it83xx/i2c_peripheral.c
@@ -4,7 +4,6 @@
*/
/* I2C module for Chrome EC */
-
#include "clock.h"
#include "compile_time_macros.h"
#include "console.h"
@@ -26,10 +25,10 @@
#define I2C_READ_MAXFIFO_DATA 16
#define I2C_ENHANCED_CH_INTERVAL 0x80
-/* Store master to slave data of channel D, E, F by DMA */
+/* Store controller to peripheral data of channel D, E, F by DMA */
static uint8_t in_data[I2C_ENHANCED_PORT_COUNT][I2C_MAX_BUFFER_SIZE]
__attribute__((section(".h2ram.pool.i2cslv")));
-/* Store slave to master data of channel D, E, F by DMA */
+/* Store peripheral to controller data of channel D, E, F by DMA */
static uint8_t out_data[I2C_ENHANCED_PORT_COUNT][I2C_MAX_BUFFER_SIZE]
__attribute__((section(".h2ram.pool.i2cslv")));
/* Store read and write data of channel A by FIFO mode */
@@ -47,17 +46,17 @@ void buffer_index_reset(void)
r_index = 0;
}
-/* Data structure to define I2C slave control configuration. */
-struct i2c_slv_ctrl_t {
- int irq; /* slave irq */
+/* Data structure to define I2C peripheral control configuration. */
+struct i2c_periph_ctrl_t {
+ int irq; /* peripheral irq */
/* offset from base 0x00F03500 register; -1 means unused. */
int offset;
enum clock_gate_offsets clock_gate;
int dma_index;
};
-/* I2C slave control */
-const struct i2c_slv_ctrl_t i2c_slv_ctrl[] = {
+/* I2C peripheral control */
+const struct i2c_periph_ctrl_t i2c_periph_ctrl[] = {
[IT83XX_I2C_CH_A] = {.irq = IT83XX_IRQ_SMB_A, .offset = -1,
.clock_gate = CGC_OFFSET_SMBA, .dma_index = -1},
[IT83XX_I2C_CH_D] = {.irq = IT83XX_IRQ_SMB_D, .offset = 0x180,
@@ -68,37 +67,37 @@ const struct i2c_slv_ctrl_t i2c_slv_ctrl[] = {
.clock_gate = CGC_OFFSET_SMBF, .dma_index = 2},
};
-void i2c_slave_read_write_data(int port)
+void i2c_peripheral_read_write_data(int port)
{
- int slv_status, i;
+ int periph_status, i;
- /* I2C slave channel A FIFO mode */
+ /* I2C peripheral channel A FIFO mode */
if (port < I2C_STANDARD_PORT_COUNT) {
int count;
- slv_status = IT83XX_SMB_SLSTA;
+ periph_status = IT83XX_SMB_SLSTA;
/* bit0-4 : FIFO byte count */
count = IT83XX_SMB_SFFSTA & 0x1F;
- /* Slave data register is waiting for read or write. */
- if (slv_status & IT83XX_SMB_SDS) {
- /* Master to read data */
- if (slv_status & IT83XX_SMB_RCS) {
+ /* Peripheral data register is waiting for read or write. */
+ if (periph_status & IT83XX_SMB_SDS) {
+ /* Controller to read data */
+ if (periph_status & IT83XX_SMB_RCS) {
for (i = 0; i < I2C_READ_MAXFIFO_DATA; i++)
- /* Return buffer data to master */
+ /* Return buffer data to controller */
IT83XX_SMB_SLDA =
pbuffer[(i + r_index) & I2C_SIZE_MASK];
/* Index to next 16 bytes of read buffer */
r_index += I2C_READ_MAXFIFO_DATA;
}
- /* Master to write data */
+ /* Controller to write data */
else {
/* FIFO Full */
if (IT83XX_SMB_SFFSTA & IT83XX_SMB_SFFFULL) {
for (i = 0; i < count; i++)
- /* Get data from master to buffer */
+ /* Get data from controller to buffer */
pbuffer[(w_index + i) &
I2C_SIZE_MASK] = IT83XX_SMB_SLDA;
}
@@ -108,19 +107,19 @@ void i2c_slave_read_write_data(int port)
}
}
/* Stop condition, indicate stop condition detected. */
- if (slv_status & IT83XX_SMB_SPDS) {
+ if (periph_status & IT83XX_SMB_SPDS) {
/* Read data less 16 bytes status */
- if (slv_status & IT83XX_SMB_RCS) {
+ if (periph_status & IT83XX_SMB_RCS) {
/* Disable FIFO mode to clear left count */
IT83XX_SMB_SFFCTL &= ~IT83XX_SMB_SAFE;
- /* Slave A FIFO Enable */
+ /* Peripheral A FIFO Enable */
IT83XX_SMB_SFFCTL |= IT83XX_SMB_SAFE;
}
- /* Master to write data */
+ /* Controller to write data */
else {
for (i = 0; i < count; i++)
- /* Get data from master to buffer */
+ /* Get data from controller to buffer */
pbuffer[(i + w_index) &
I2C_SIZE_MASK] = IT83XX_SMB_SLDA;
}
@@ -128,31 +127,31 @@ void i2c_slave_read_write_data(int port)
/* Reset read and write buffer index */
buffer_index_reset();
}
- /* Slave time status, timeout status occurs. */
- if (slv_status & IT83XX_SMB_STS) {
+ /* Peripheral time status, timeout status occurs. */
+ if (periph_status & IT83XX_SMB_STS) {
/* Reset read and write buffer index */
buffer_index_reset();
}
- /* Write clear the slave status */
- IT83XX_SMB_SLSTA = slv_status;
+ /* Write clear the peripheral status */
+ IT83XX_SMB_SLSTA = periph_status;
}
- /* Enhanced I2C slave channel D, E, F DMA mode */
+ /* Enhanced I2C peripheral channel D, E, F DMA mode */
else {
int ch, idx;
/* Get enhanced i2c channel */
- ch = i2c_slv_ctrl[port].offset / I2C_ENHANCED_CH_INTERVAL;
+ ch = i2c_periph_ctrl[port].offset / I2C_ENHANCED_CH_INTERVAL;
- idx = i2c_slv_ctrl[port].dma_index;
+ idx = i2c_periph_ctrl[port].dma_index;
/* Interrupt pending */
if (IT83XX_I2C_STR(ch) & IT83XX_I2C_INTPEND) {
- slv_status = IT83XX_I2C_IRQ_ST(ch);
+ periph_status = IT83XX_I2C_IRQ_ST(ch);
- /* Master to read data */
- if (slv_status & IT83XX_I2C_IDR_CLR) {
+ /* Controller to read data */
+ if (periph_status & IT83XX_I2C_IDR_CLR) {
/*
* TODO(b:129360157): Return buffer data by
* "out_data" array.
@@ -161,16 +160,16 @@ void i2c_slave_read_write_data(int port)
for (i = 0; i < I2C_MAX_BUFFER_SIZE; i++)
out_data[idx][i] = i;
}
- /* Master to write data */
- if (slv_status & IT83XX_I2C_IDW_CLR) {
- /* Master to write data finish flag */
+ /* Controller to write data */
+ if (periph_status & IT83XX_I2C_IDW_CLR) {
+ /* Controller to write data finish flag */
wr_done[idx] = 1;
}
- /* Slave finish */
- if (slv_status & IT83XX_I2C_P_CLR) {
+ /* Peripheral finish */
+ if (periph_status & IT83XX_I2C_P_CLR) {
if (wr_done[idx]) {
/*
- * TODO(b:129360157): Handle master write
+ * TODO(b:129360157): Handle controller write
* data by "in_data" array.
*/
CPRINTS("WData: %ph",
@@ -180,8 +179,8 @@ void i2c_slave_read_write_data(int port)
}
}
- /* Write clear the slave status */
- IT83XX_I2C_IRQ_ST(ch) = slv_status;
+ /* Write clear the peripheral status */
+ IT83XX_I2C_IRQ_ST(ch) = periph_status;
}
/* Hardware reset */
@@ -189,54 +188,54 @@ void i2c_slave_read_write_data(int port)
}
}
-void i2c_slv_interrupt(int port)
+void i2c_periph_interrupt(int port)
{
- /* Slave to read and write fifo data */
- i2c_slave_read_write_data(port);
+ /* Peripheral to read and write fifo data */
+ i2c_peripheral_read_write_data(port);
/* Clear the interrupt status */
- task_clear_pending_irq(i2c_slv_ctrl[port].irq);
+ task_clear_pending_irq(i2c_periph_ctrl[port].irq);
}
-void i2c_slave_enable(int port, uint8_t slv_addr)
+void i2c_peripheral_enable(int port, uint8_t periph_addr)
{
- clock_enable_peripheral(i2c_slv_ctrl[port].clock_gate, 0, 0);
+ clock_enable_peripheral(i2c_periph_ctrl[port].clock_gate, 0, 0);
- /* I2C slave channel A FIFO mode */
+ /* I2C peripheral channel A FIFO mode */
if (port < I2C_STANDARD_PORT_COUNT) {
/* This field defines the SMCLK0/1/2 clock/data low timeout. */
IT83XX_SMB_25MS = I2C_CLK_LOW_TIMEOUT;
- /* bit0 : Slave A FIFO Enable */
+ /* bit0 : Peripheral A FIFO Enable */
IT83XX_SMB_SFFCTL |= IT83XX_SMB_SAFE;
/*
- * bit1 : Slave interrupt enable.
+ * bit1 : Peripheral interrupt enable.
* bit2 : SMCLK/SMDAT will be released if timeout.
- * bit3 : Slave detect STOP condition interrupt enable.
+ * bit3 : Peripheral detect STOP condition interrupt enable.
*/
IT83XX_SMB_SICR = 0x0E;
- /* Slave address 1 */
- IT83XX_SMB_RESLADR = slv_addr;
+ /* Peripheral address 1 */
+ IT83XX_SMB_RESLADR = periph_addr;
- /* Write clear all slave status */
+ /* Write clear all peripheral status */
IT83XX_SMB_SLSTA = 0xE7;
- /* bit5 : Enable the SMBus slave device */
+ /* bit5 : Enable the SMBus peripheral device */
IT83XX_SMB_HOCTL2(port) |= IT83XX_SMB_SLVEN;
}
- /* Enhanced I2C slave channel D, E, F DMA mode */
+ /* Enhanced I2C peripheral channel D, E, F DMA mode */
else {
int ch, idx;
uint32_t in_data_addr, out_data_addr;
/* Get enhanced i2c channel */
- ch = i2c_slv_ctrl[port].offset / I2C_ENHANCED_CH_INTERVAL;
+ ch = i2c_periph_ctrl[port].offset / I2C_ENHANCED_CH_INTERVAL;
- idx = i2c_slv_ctrl[port].dma_index;
+ idx = i2c_periph_ctrl[port].dma_index;
switch (port) {
case IT83XX_I2C_CH_D:
@@ -263,18 +262,18 @@ void i2c_slave_enable(int port, uint8_t slv_addr)
/* Bit stretching */
IT83XX_I2C_TOS(ch) |= IT83XX_I2C_CLK_STR;
- /* Slave address(8-bit)*/
- IT83XX_I2C_IDR(ch) = slv_addr << 1;
+ /* Peripheral address(8-bit)*/
+ IT83XX_I2C_IDR(ch) = periph_addr << 1;
/* I2C interrupt enable and set acknowledge */
IT83XX_I2C_CTR(ch) = IT83XX_I2C_HALT |
IT83XX_I2C_INTEN | IT83XX_I2C_ACK;
/*
- * bit3 : Slave ID write flag
- * bit2 : Slave ID read flag
- * bit1 : Slave received data flag
- * bit0 : Slave finish
+ * bit3 : Peripheral ID write flag
+ * bit2 : Peripheral ID read flag
+ * bit1 : Peripheral received data flag
+ * bit0 : Peripheral finish
*/
IT83XX_I2C_IRQ_ST(ch) = 0xFF;
@@ -319,27 +318,27 @@ void i2c_slave_enable(int port, uint8_t slv_addr)
}
}
-static void i2c_slave_init(void)
+static void i2c_peripheral_init(void)
{
int i, p;
/* DLM 52k~56k size select enable */
IT83XX_GCTRL_MCCR2 |= (1 << 4);
- /* Enable I2C Slave function */
- for (i = 0; i < i2c_slvs_used; i++) {
+ /* Enable I2C Peripheral function */
+ for (i = 0; i < i2c_periphs_used; i++) {
- /* I2c slave port mapping. */
- p = i2c_slv_ports[i].port;
+ /* I2c peripheral port mapping. */
+ p = i2c_periph_ports[i].port;
- /* To enable slave ch[x] */
- i2c_slave_enable(p, i2c_slv_ports[i].slave_adr);
+ /* To enable peripheral ch[x] */
+ i2c_peripheral_enable(p, i2c_periph_ports[i].addr);
/* Clear the interrupt status */
- task_clear_pending_irq(i2c_slv_ctrl[p].irq);
+ task_clear_pending_irq(i2c_periph_ctrl[p].irq);
/* enable i2c interrupt */
- task_enable_irq(i2c_slv_ctrl[p].irq);
+ task_enable_irq(i2c_periph_ctrl[p].irq);
}
}
-DECLARE_HOOK(HOOK_INIT, i2c_slave_init, HOOK_PRIO_INIT_I2C + 1);
+DECLARE_HOOK(HOOK_INIT, i2c_peripheral_init, HOOK_PRIO_INIT_I2C + 1);
diff --git a/chip/it83xx/intc.c b/chip/it83xx/intc.c
index 8f96da17d0..057e51293a 100644
--- a/chip/it83xx/intc.c
+++ b/chip/it83xx/intc.c
@@ -228,7 +228,7 @@ void intc_cpu_int_group_6(void)
case IT83XX_IRQ_SMB_A:
#ifdef CONFIG_I2C_PERIPHERAL
if (IT83XX_SMB_SFFCTL & IT83XX_SMB_SAFE)
- i2c_slv_interrupt(IT83XX_I2C_CH_A);
+ i2c_periph_interrupt(IT83XX_I2C_CH_A);
else
#endif
i2c_interrupt(IT83XX_I2C_CH_A);
@@ -245,7 +245,7 @@ void intc_cpu_int_group_6(void)
case IT83XX_IRQ_SMB_D:
#ifdef CONFIG_I2C_PERIPHERAL
if (!(IT83XX_I2C_CTR(3) & IT83XX_I2C_MODE))
- i2c_slv_interrupt(IT83XX_I2C_CH_D);
+ i2c_periph_interrupt(IT83XX_I2C_CH_D);
else
#endif
i2c_interrupt(IT83XX_I2C_CH_D);
@@ -254,7 +254,7 @@ void intc_cpu_int_group_6(void)
case IT83XX_IRQ_SMB_E:
#ifdef CONFIG_I2C_PERIPHERAL
if (!(IT83XX_I2C_CTR(0) & IT83XX_I2C_MODE))
- i2c_slv_interrupt(IT83XX_I2C_CH_E);
+ i2c_periph_interrupt(IT83XX_I2C_CH_E);
else
#endif
i2c_interrupt(IT83XX_I2C_CH_E);
@@ -263,7 +263,7 @@ void intc_cpu_int_group_6(void)
case IT83XX_IRQ_SMB_F:
#ifdef CONFIG_I2C_PERIPHERAL
if (!(IT83XX_I2C_CTR(1) & IT83XX_I2C_MODE))
- i2c_slv_interrupt(IT83XX_I2C_CH_F);
+ i2c_periph_interrupt(IT83XX_I2C_CH_F);
else
#endif
i2c_interrupt(IT83XX_I2C_CH_F);
diff --git a/chip/it83xx/intc.h b/chip/it83xx/intc.h
index 97639c9a0e..c407e6e155 100644
--- a/chip/it83xx/intc.h
+++ b/chip/it83xx/intc.h
@@ -32,7 +32,7 @@ void voltage_comparator_interrupt(void);
#endif
void i2c_interrupt(int port);
#ifdef CONFIG_I2C_PERIPHERAL
-void i2c_slv_interrupt(int port);
+void i2c_periph_interrupt(int port);
#endif
void clock_sleep_mode_wakeup_isr(void);
int clock_ec_wake_from_sleep(void);
diff --git a/include/i2c_peripheral.h b/include/i2c_peripheral.h
index 3145d4679b..488e886b0e 100644
--- a/include/i2c_peripheral.h
+++ b/include/i2c_peripheral.h
@@ -3,19 +3,19 @@
* found in the LICENSE file.
*/
-/* I2C slave interface for Chrome EC */
+/* I2C peripheral interface for Chrome EC */
-#ifndef __CROS_EC_I2CSLV_H
-#define __CROS_EC_I2CSLV_H
+#ifndef __CROS_EC_I2C_PERIPHERAL_H
+#define __CROS_EC_I2C_PERIPHERAL_H
-/* Data structure to define I2C slave port configuration. */
-struct i2c_slv_port_t {
+/* Data structure to define I2C peripheral port configuration. */
+struct i2c_periph_port_t {
const char *name; /* Port name */
int port; /* Port */
- uint8_t slave_adr; /* slave address(7-bit without R/W) */
+ uint8_t addr; /* address(7-bit without R/W) */
};
-extern const struct i2c_slv_port_t i2c_slv_ports[];
-extern const unsigned int i2c_slvs_used;
+extern const struct i2c_periph_port_t i2c_periph_ports[];
+extern const unsigned int i2c_periphs_used;
-#endif /* __CROS_EC_I2CSLV_H */
+#endif /* __CROS_EC_I2C_PERIPHERAL_H */