drivers: i2c: Add support for cc32xx I2C bus
This was validated on the cc3220sf_launchxl board using the Zephyr thermometer sample program adapted to call the i2c driver directly, and fetching samples from the on-board TMP006 temperature sensor. Signed-off-by: Gil Pitney <gil.pitney@linaro.org>
This commit is contained in:
parent
8e30c6e790
commit
e5cef70abd
10 changed files with 515 additions and 0 deletions
|
@ -6,4 +6,11 @@ if BOARD_CC3220SF_LAUNCHXL
|
|||
config BOARD
|
||||
default cc3220sf_launchxl
|
||||
|
||||
if I2C
|
||||
|
||||
config I2C_CC32XX
|
||||
def_bool y
|
||||
|
||||
endif # I2C
|
||||
|
||||
endif # BOARD_CC3220SF_LAUNCHXL
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
aliases {
|
||||
uart_0 = &uart0;
|
||||
uart_1 = &uart1;
|
||||
i2c_0 = &i2c0;
|
||||
};
|
||||
|
||||
chosen {
|
||||
|
@ -22,3 +23,8 @@
|
|||
status = "ok";
|
||||
current-speed = <115200>;
|
||||
};
|
||||
|
||||
&i2c0 {
|
||||
status = "ok";
|
||||
clock-frequency = <I2C_BITRATE_FAST>;
|
||||
};
|
||||
|
|
|
@ -57,6 +57,14 @@ driver support.
|
|||
+-----------+------------+-----------------------+
|
||||
| GPIO | on-chip | gpio |
|
||||
+-----------+------------+-----------------------+
|
||||
| I2C | on-chip | i2c |
|
||||
+-----------+------------+-----------------------+
|
||||
|
||||
.. note::
|
||||
|
||||
For consistency with TI SimpleLink SDK and BoosterPack examples,
|
||||
the I2C driver defaults to I2C_BITRATE_FAST mode (400 kHz) bus speed
|
||||
on bootup.
|
||||
|
||||
The accelerometer, temperature sensors, or other peripherals
|
||||
accessible through the BoosterPack, are not currently supported.
|
||||
|
|
|
@ -1,2 +1,8 @@
|
|||
#define CONFIG_NUM_IRQ_PRIO_BITS ARM_V7M_NVIC_E000E100_ARM_NUM_IRQ_PRIORITY_BITS
|
||||
#define CONFIG_UART_CC32XX_NAME TI_CC32XX_UART_4000C000_LABEL
|
||||
|
||||
#define CONFIG_I2C_0_LABEL TI_CC32XX_I2C_40020000_LABEL
|
||||
#define CONFIG_I2C_0_BASE_ADDRESS TI_CC32XX_I2C_40020000_BASE_ADDRESS_0
|
||||
#define CONFIG_I2C_0_BITRATE TI_CC32XX_I2C_40020000_CLOCK_FREQUENCY
|
||||
#define CONFIG_I2C_0_IRQ TI_CC32XX_I2C_40020000_IRQ_0
|
||||
#define CONFIG_I2C_0_IRQ_PRIORITY TI_CC32XX_I2C_40020000_IRQ_0_PRIORITY
|
||||
|
|
|
@ -67,6 +67,29 @@
|
|||
#include <driverlib/rom_map.h>
|
||||
#include <driverlib/gpio.h>
|
||||
#include <driverlib/prcm.h>
|
||||
#include <driverlib/i2c.h>
|
||||
|
||||
/* Defines taken from SimpleLink SDK's I2CCC32XX.h: */
|
||||
/*
|
||||
* Macros defining possible I2C signal pin mux options
|
||||
*
|
||||
* The bits in the pin mode macros are as follows:
|
||||
* The lower 8 bits of the macro refer to the pin, offset by 1, to match
|
||||
* driverlib pin defines. For example, I2C_CC32XX_PIN_01_I2C_SCL & 0xff = 0,
|
||||
* which equals PIN_01 in driverlib pin.h. By matching the PIN_xx defines in
|
||||
* driverlib pin.h, we can pass the pin directly to the driverlib functions.
|
||||
* The upper 8 bits of the macro correspond to the pin mux confg mode
|
||||
* value for the pin to operate in the I2C mode. For example, pin 1 is
|
||||
* configured with mode 1 to operate as I2C_SCL.
|
||||
*/
|
||||
#define I2C_CC32XX_PIN_01_I2C_SCL 0x100 /*!< PIN 1 is used for I2C_SCL */
|
||||
#define I2C_CC32XX_PIN_02_I2C_SDA 0x101 /*!< PIN 2 is used for I2C_SDA */
|
||||
#define I2C_CC32XX_PIN_03_I2C_SCL 0x502 /*!< PIN 3 is used for I2C_SCL */
|
||||
#define I2C_CC32XX_PIN_04_I2C_SDA 0x503 /*!< PIN 4 is used for I2C_SDA */
|
||||
#define I2C_CC32XX_PIN_05_I2C_SCL 0x504 /*!< PIN 5 is used for I2C_SCL */
|
||||
#define I2C_CC32XX_PIN_06_I2C_SDA 0x505 /*!< PIN 6 is used for I2C_SDA */
|
||||
#define I2C_CC32XX_PIN_16_I2C_SCL 0x90F /*!< PIN 16 is used for I2C_SCL */
|
||||
#define I2C_CC32XX_PIN_17_I2C_SDA 0x910 /*!< PIN 17 is used for I2C_SDA */
|
||||
|
||||
int pinmux_initialize(struct device *port)
|
||||
{
|
||||
|
@ -113,6 +136,29 @@ int pinmux_initialize(struct device *port)
|
|||
|
||||
#ifdef CONFIG_GPIO_CC32XX_A3
|
||||
MAP_PRCMPeripheralClkEnable(PRCM_GPIOA3, PRCM_RUN_MODE_CLK);
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_I2C_CC32XX
|
||||
{
|
||||
unsigned long pin;
|
||||
unsigned long mode;
|
||||
|
||||
/* Enable the I2C module clocks and wait for completion:*/
|
||||
MAP_PRCMPeripheralClkEnable(PRCM_I2CA0,
|
||||
PRCM_RUN_MODE_CLK |
|
||||
PRCM_SLP_MODE_CLK);
|
||||
while (!MAP_PRCMPeripheralStatusGet(PRCM_I2CA0)) {
|
||||
}
|
||||
|
||||
pin = I2C_CC32XX_PIN_01_I2C_SCL & 0xff;
|
||||
mode = (I2C_CC32XX_PIN_01_I2C_SCL >> 8) & 0xff;
|
||||
MAP_PinTypeI2C(pin, mode);
|
||||
|
||||
pin = I2C_CC32XX_PIN_02_I2C_SDA & 0xff;
|
||||
mode = (I2C_CC32XX_PIN_02_I2C_SDA >> 8) & 0xff;
|
||||
MAP_PinTypeI2C(pin, mode);
|
||||
}
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
zephyr_sources_ifdef(CONFIG_I2C_ATMEL_SAM3 i2c_atmel_sam3.c)
|
||||
zephyr_sources_ifdef(CONFIG_I2C_BITBANG i2c_bitbang.c)
|
||||
zephyr_sources_ifdef(CONFIG_I2C_CC32XX i2c_cc32xx.c)
|
||||
zephyr_sources_ifdef(CONFIG_I2C_DW i2c_dw.c)
|
||||
zephyr_sources_ifdef(CONFIG_I2C_ESP32 i2c_esp32.c)
|
||||
zephyr_sources_ifdef(CONFIG_I2C_GPIO i2c_gpio.c)
|
||||
|
|
|
@ -89,6 +89,14 @@ config I2C_NRF5
|
|||
This option enables the I2C driver for Nordic Semiconductor nRF5
|
||||
family processors.
|
||||
|
||||
config I2C_CC32XX
|
||||
bool "CC32XX I2C driver"
|
||||
depends on SOC_SERIES_CC32XX
|
||||
select HAS_DTS_I2C
|
||||
default n
|
||||
help
|
||||
Enable the CC32XX I2C driver.
|
||||
|
||||
config I2C_NRF5_GPIO_SCA_PIN
|
||||
int "SCA Pin Number"
|
||||
range 0 31
|
||||
|
|
389
drivers/i2c/i2c_cc32xx.c
Normal file
389
drivers/i2c/i2c_cc32xx.c
Normal file
|
@ -0,0 +1,389 @@
|
|||
/*
|
||||
* Copyright (c) 2017, Texas Instruments Incorporated
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
/* The logic here is adapted from SimpleLink SDK's I2CCC32XX.c module. */
|
||||
|
||||
#include <kernel.h>
|
||||
#include <errno.h>
|
||||
#include <i2c.h>
|
||||
#include <soc.h>
|
||||
#include "i2c-priv.h"
|
||||
|
||||
/* Driverlib includes */
|
||||
#include <inc/hw_memmap.h>
|
||||
#include <inc/hw_common_reg.h>
|
||||
#include <driverlib/rom.h>
|
||||
#include <driverlib/rom_map.h>
|
||||
#include <driverlib/i2c.h>
|
||||
|
||||
#define I2C_MASTER_CMD_BURST_RECEIVE_START_NACK I2C_MASTER_CMD_BURST_SEND_START
|
||||
#define I2C_MASTER_CMD_BURST_RECEIVE_STOP \
|
||||
I2C_MASTER_CMD_BURST_RECEIVE_ERROR_STOP
|
||||
#define I2C_MASTER_CMD_BURST_RECEIVE_CONT_NACK I2C_MASTER_CMD_BURST_SEND_CONT
|
||||
|
||||
#define I2C_SEM_MASK \
|
||||
COMMON_REG_I2C_Properties_Register_I2C_Properties_Register_M
|
||||
#define I2C_SEM_TAKE \
|
||||
COMMON_REG_I2C_Properties_Register_I2C_Properties_Register_S
|
||||
|
||||
#define IS_I2C_MSG_WRITE(flags) ((flags & I2C_MSG_RW_MASK) == I2C_MSG_WRITE)
|
||||
|
||||
#define DEV_CFG(dev) \
|
||||
((const struct i2c_cc32xx_config *const)(dev)->config->config_info)
|
||||
#define DEV_DATA(dev) \
|
||||
((struct i2c_cc32xx_data *const)(dev)->driver_data)
|
||||
#define DEV_BASE(dev) \
|
||||
((DEV_CFG(dev))->base)
|
||||
|
||||
|
||||
/* Since this driver does not explicitly enable the TX/RX FIFOs, there
|
||||
* are no interrupts received which can distinguish between read and write
|
||||
* completion.
|
||||
* So, we need the READ and WRITE state flags to determine whether the
|
||||
* completed transmission was started as a write or a read.
|
||||
* The ERROR flag is used to convey error status from the ISR back to the
|
||||
* I2C API without having to re-read I2C registers.
|
||||
*/
|
||||
enum i2c_cc32xx_state {
|
||||
/* I2C was primed for a write operation */
|
||||
I2C_CC32XX_WRITE_MODE,
|
||||
/* I2C was primed for a read operation */
|
||||
I2C_CC32XX_READ_MODE,
|
||||
/* I2C error occurred */
|
||||
I2C_CC32XX_ERROR = 0xFF
|
||||
};
|
||||
|
||||
struct i2c_cc32xx_config {
|
||||
u32_t base;
|
||||
u32_t bitrate;
|
||||
unsigned int irq_no;
|
||||
};
|
||||
|
||||
struct i2c_cc32xx_data {
|
||||
struct k_sem mutex;
|
||||
struct k_sem transfer_complete;
|
||||
|
||||
volatile enum i2c_cc32xx_state state;
|
||||
|
||||
struct i2c_msg msg; /* Cache msg for transfer state machine */
|
||||
u16_t slave_addr; /* Cache slave address for ISR use */
|
||||
};
|
||||
|
||||
static void configure_i2c_irq(const struct i2c_cc32xx_config *config);
|
||||
|
||||
static int i2c_cc32xx_configure(struct device *dev, u32_t dev_config_raw)
|
||||
{
|
||||
u32_t base = DEV_BASE(dev);
|
||||
u32_t bitrate_id;
|
||||
|
||||
if (!(dev_config_raw & I2C_MODE_MASTER)) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (dev_config_raw & I2C_ADDR_10_BITS) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
switch (I2C_SPEED_GET(dev_config_raw)) {
|
||||
case I2C_SPEED_STANDARD:
|
||||
bitrate_id = 0;
|
||||
break;
|
||||
case I2C_SPEED_FAST:
|
||||
bitrate_id = 1;
|
||||
break;
|
||||
default:
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
MAP_I2CMasterInitExpClk(base, CONFIG_SYS_CLOCK_HW_CYCLES_PER_SEC,
|
||||
bitrate_id);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void _i2c_cc32xx_prime_transfer(struct device *dev, struct i2c_msg *msg,
|
||||
u16_t addr)
|
||||
{
|
||||
struct i2c_cc32xx_data *data = DEV_DATA(dev);
|
||||
u32_t base = DEV_BASE(dev);
|
||||
|
||||
/* Initialize internal counters and buf pointers: */
|
||||
data->msg = *msg;
|
||||
data->slave_addr = addr;
|
||||
|
||||
/* Start transfer in Transmit mode */
|
||||
if (IS_I2C_MSG_WRITE(data->msg.flags)) {
|
||||
|
||||
/* Specify the I2C slave address */
|
||||
MAP_I2CMasterSlaveAddrSet(base, addr, false);
|
||||
|
||||
/* Update the I2C state */
|
||||
data->state = I2C_CC32XX_WRITE_MODE;
|
||||
|
||||
/* Write data contents into data register */
|
||||
MAP_I2CMasterDataPut(base, *((data->msg.buf)++));
|
||||
|
||||
/* Start the I2C transfer in master transmit mode */
|
||||
MAP_I2CMasterControl(base, I2C_MASTER_CMD_BURST_SEND_START);
|
||||
|
||||
} else {
|
||||
/* Start transfer in Receive mode */
|
||||
/* Specify the I2C slave address */
|
||||
MAP_I2CMasterSlaveAddrSet(base, addr, true);
|
||||
|
||||
/* Update the I2C mode */
|
||||
data->state = I2C_CC32XX_READ_MODE;
|
||||
|
||||
if (data->msg.len < 2) {
|
||||
/* Start the I2C transfer in master receive mode */
|
||||
MAP_I2CMasterControl(base,
|
||||
I2C_MASTER_CMD_BURST_RECEIVE_START_NACK);
|
||||
} else {
|
||||
/* Start the I2C transfer in burst receive mode */
|
||||
MAP_I2CMasterControl(base,
|
||||
I2C_MASTER_CMD_BURST_RECEIVE_START);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int i2c_cc32xx_transfer(struct device *dev, struct i2c_msg *msgs,
|
||||
u8_t num_msgs, u16_t addr)
|
||||
{
|
||||
struct i2c_cc32xx_data *data = DEV_DATA(dev);
|
||||
int retval = 0;
|
||||
|
||||
/* Acquire the driver mutex */
|
||||
k_sem_take(&data->mutex, K_FOREVER);
|
||||
|
||||
/* Iterate over all the messages */
|
||||
for (int i = 0; i < num_msgs; i++) {
|
||||
|
||||
/* Begin the transfer */
|
||||
_i2c_cc32xx_prime_transfer(dev, msgs, addr);
|
||||
|
||||
/* Wait for the transfer to complete */
|
||||
k_sem_take(&data->transfer_complete, K_FOREVER);
|
||||
|
||||
/* Return an error if the transfer didn't complete */
|
||||
if (data->state == I2C_CC32XX_ERROR) {
|
||||
retval = -EIO;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Move to the next message */
|
||||
msgs++;
|
||||
}
|
||||
|
||||
/* Release the mutex */
|
||||
k_sem_give(&data->mutex);
|
||||
|
||||
return retval;
|
||||
}
|
||||
|
||||
static void _i2c_cc32xx_isr_handle_write(u32_t base,
|
||||
struct i2c_cc32xx_data *data)
|
||||
{
|
||||
/* Decrement write Counter */
|
||||
data->msg.len--;
|
||||
|
||||
/* Check if more data needs to be sent */
|
||||
if (data->msg.len) {
|
||||
|
||||
/* Write data contents into data register */
|
||||
MAP_I2CMasterDataPut(base, *(data->msg.buf));
|
||||
data->msg.buf++;
|
||||
|
||||
if (data->msg.len < 2) {
|
||||
/* Everything has been sent, nothing to receive */
|
||||
/* Send last byte with STOP bit */
|
||||
MAP_I2CMasterControl(base,
|
||||
I2C_MASTER_CMD_BURST_SEND_FINISH);
|
||||
} else {
|
||||
/*
|
||||
* Either there is more data to be transmitted or some
|
||||
* data needs to be received next
|
||||
*/
|
||||
MAP_I2CMasterControl(base,
|
||||
I2C_MASTER_CMD_BURST_SEND_CONT);
|
||||
|
||||
}
|
||||
} else {
|
||||
/*
|
||||
* No more data needs to be sent, so follow up with
|
||||
* a STOP bit.
|
||||
*/
|
||||
MAP_I2CMasterControl(base,
|
||||
I2C_MASTER_CMD_BURST_RECEIVE_STOP);
|
||||
}
|
||||
}
|
||||
|
||||
static void _i2c_cc32xx_isr_handle_read(u32_t base,
|
||||
struct i2c_cc32xx_data *data)
|
||||
{
|
||||
|
||||
/* Save the received data */
|
||||
*(data->msg.buf) = MAP_I2CMasterDataGet(base);
|
||||
data->msg.buf++;
|
||||
|
||||
/* Check if any data needs to be received */
|
||||
data->msg.len--;
|
||||
if (data->msg.len) {
|
||||
if (data->msg.len > 1) {
|
||||
/* More data to be received */
|
||||
MAP_I2CMasterControl(base,
|
||||
I2C_MASTER_CMD_BURST_RECEIVE_CONT);
|
||||
} else {
|
||||
/*
|
||||
* Send NACK because it's the last byte to be received
|
||||
*/
|
||||
MAP_I2CMasterControl(base,
|
||||
I2C_MASTER_CMD_BURST_RECEIVE_CONT_NACK);
|
||||
}
|
||||
} else {
|
||||
/*
|
||||
* No more data needs to be received, so follow up with a
|
||||
* STOP bit
|
||||
*/
|
||||
MAP_I2CMasterControl(base,
|
||||
I2C_MASTER_CMD_BURST_RECEIVE_STOP);
|
||||
}
|
||||
}
|
||||
|
||||
static void i2c_cc32xx_isr(void *arg)
|
||||
{
|
||||
struct device *dev = (struct device *)arg;
|
||||
u32_t base = DEV_BASE(dev);
|
||||
struct i2c_cc32xx_data *data = DEV_DATA(dev);
|
||||
u32_t err_status;
|
||||
u32_t int_status;
|
||||
|
||||
/* Get the error status of the I2C controller */
|
||||
err_status = MAP_I2CMasterErr(base);
|
||||
|
||||
/* Get interrupt cause (from I2CMRIS (raw interrupt) reg): */
|
||||
int_status = MAP_I2CMasterIntStatusEx(base, 0);
|
||||
|
||||
/* Clear interrupt source to avoid additional interrupts */
|
||||
MAP_I2CMasterIntClearEx(base, int_status);
|
||||
|
||||
SYS_LOG_DBG("primed state: %d; err_status: 0x%x; int_status: 0x%x",
|
||||
data->state, err_status, int_status);
|
||||
|
||||
/* Handle errors: */
|
||||
if ((err_status != I2C_MASTER_ERR_NONE) ||
|
||||
(int_status &
|
||||
(I2C_MASTER_INT_ARB_LOST | I2C_MASTER_INT_TIMEOUT))) {
|
||||
|
||||
/* Set so API can report I/O error: */
|
||||
data->state = I2C_CC32XX_ERROR;
|
||||
|
||||
if (!(err_status & (I2C_MASTER_ERR_ARB_LOST |
|
||||
I2C_MASTER_ERR_ADDR_ACK))) {
|
||||
/* Send a STOP bit to end I2C communications */
|
||||
/*
|
||||
* I2C_MASTER_CMD_BURST_SEND_ERROR_STOP -and-
|
||||
* I2C_MASTER_CMD_BURST_RECEIVE_ERROR_STOP
|
||||
* have the same values
|
||||
*/
|
||||
MAP_I2CMasterControl(base,
|
||||
I2C_MASTER_CMD_BURST_SEND_ERROR_STOP);
|
||||
}
|
||||
/* Indicate transfer complete */
|
||||
k_sem_give(&data->transfer_complete);
|
||||
|
||||
/* Handle Stop: */
|
||||
} else if (int_status & I2C_MASTER_INT_STOP) {
|
||||
/* Indicate transfer complete */
|
||||
k_sem_give(&data->transfer_complete);
|
||||
|
||||
/* Handle (read or write) transmit complete: */
|
||||
} else if (int_status & (I2C_MASTER_INT_DATA | I2C_MASTER_INT_START)) {
|
||||
if (data->state == I2C_CC32XX_WRITE_MODE) {
|
||||
_i2c_cc32xx_isr_handle_write(base, data);
|
||||
}
|
||||
if (data->state == I2C_CC32XX_READ_MODE) {
|
||||
_i2c_cc32xx_isr_handle_read(base, data);
|
||||
}
|
||||
/* Some unanticipated H/W state: */
|
||||
} else {
|
||||
__ASSERT(1, "Unanticipated I2C Interrupt!");
|
||||
data->state = I2C_CC32XX_ERROR;
|
||||
k_sem_give(&data->transfer_complete);
|
||||
}
|
||||
}
|
||||
|
||||
static int i2c_cc32xx_init(struct device *dev)
|
||||
{
|
||||
u32_t base = DEV_BASE(dev);
|
||||
const struct i2c_cc32xx_config *config = DEV_CFG(dev);
|
||||
struct i2c_cc32xx_data *data = DEV_DATA(dev);
|
||||
u32_t bitrate_cfg;
|
||||
int error;
|
||||
u32_t regval;
|
||||
|
||||
k_sem_init(&data->mutex, 1, UINT_MAX);
|
||||
k_sem_init(&data->transfer_complete, 0, UINT_MAX);
|
||||
|
||||
/* In case of app restart: disable I2C module, clear NVIC interrupt */
|
||||
/* Note: this was done *during* pinmux setup in SimpleLink SDK. */
|
||||
MAP_I2CMasterDisable(base);
|
||||
|
||||
/* Clear exception INT_I2CA0 */
|
||||
MAP_IntPendClear((unsigned long)(config->irq_no + 16));
|
||||
|
||||
configure_i2c_irq(config);
|
||||
|
||||
/* Take I2C hardware semaphore. */
|
||||
regval = HWREG(COMMON_REG_BASE);
|
||||
regval = (regval & ~I2C_SEM_MASK) | (0x01 << I2C_SEM_TAKE);
|
||||
HWREG(COMMON_REG_BASE) = regval;
|
||||
|
||||
/* Set to default configuration: */
|
||||
bitrate_cfg = _i2c_map_dt_bitrate(config->bitrate);
|
||||
error = i2c_cc32xx_configure(dev, I2C_MODE_MASTER | bitrate_cfg);
|
||||
if (error) {
|
||||
return error;
|
||||
}
|
||||
|
||||
/* Clear any pending interrupts */
|
||||
MAP_I2CMasterIntClear(base);
|
||||
|
||||
/* Enable the I2C Master for operation */
|
||||
MAP_I2CMasterEnable(base);
|
||||
|
||||
/* Unmask I2C interrupts */
|
||||
MAP_I2CMasterIntEnable(base);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static const struct i2c_driver_api i2c_cc32xx_driver_api = {
|
||||
.configure = i2c_cc32xx_configure,
|
||||
.transfer = i2c_cc32xx_transfer,
|
||||
};
|
||||
|
||||
|
||||
static const struct i2c_cc32xx_config i2c_cc32xx_config = {
|
||||
.base = CONFIG_I2C_0_BASE_ADDRESS,
|
||||
.bitrate = CONFIG_I2C_0_BITRATE,
|
||||
.irq_no = CONFIG_I2C_0_IRQ,
|
||||
};
|
||||
|
||||
static struct i2c_cc32xx_data i2c_cc32xx_data;
|
||||
|
||||
DEVICE_AND_API_INIT(i2c_cc32xx, CONFIG_I2C_0_LABEL, &i2c_cc32xx_init,
|
||||
&i2c_cc32xx_data, &i2c_cc32xx_config,
|
||||
POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEVICE,
|
||||
&i2c_cc32xx_driver_api);
|
||||
|
||||
static void configure_i2c_irq(const struct i2c_cc32xx_config *config)
|
||||
{
|
||||
IRQ_CONNECT(CONFIG_I2C_0_IRQ,
|
||||
CONFIG_I2C_0_IRQ_PRIORITY,
|
||||
i2c_cc32xx_isr, DEVICE_GET(i2c_cc32xx), 0);
|
||||
|
||||
irq_enable(config->irq_no);
|
||||
}
|
|
@ -1,14 +1,17 @@
|
|||
#include <arm/armv7-m.dtsi>
|
||||
|
||||
#include <ti/mem.h>
|
||||
#include <dt-bindings/i2c/i2c.h>
|
||||
|
||||
#define INT_UARTA0 21 // UART0 Rx and Tx
|
||||
#define INT_UARTA1 22 // UART1 Rx and Tx
|
||||
#define INT_I2CA0 24 // I2C controller
|
||||
|
||||
/* Note: Zephyr uses exception numbers, vs the IRQ #s used by the CC32XX SDK */
|
||||
/* which are offset by 16: */
|
||||
#define EXP_UARTA0 (INT_UARTA0 - 16)
|
||||
#define EXP_UARTA1 (INT_UARTA1 - 16)
|
||||
#define EXP_I2CA0 (INT_I2CA0 - 16)
|
||||
|
||||
/ {
|
||||
cpus {
|
||||
|
@ -56,6 +59,17 @@
|
|||
label = "UART_1";
|
||||
};
|
||||
|
||||
i2c0: i2c@40020000 {
|
||||
compatible = "ti,cc32xx-i2c";
|
||||
clock-frequency = <I2C_BITRATE_STANDARD>;
|
||||
#address-cells = <1>;
|
||||
#size-cells = <0>;
|
||||
reg = <0x40020000 0xfc8>;
|
||||
interrupts = <EXP_I2CA0 3>;
|
||||
status = "disabled";
|
||||
label= "I2C_0";
|
||||
};
|
||||
|
||||
};
|
||||
};
|
||||
|
||||
|
|
30
dts/bindings/i2c/ti,cc32xx-i2c.yaml
Normal file
30
dts/bindings/i2c/ti,cc32xx-i2c.yaml
Normal file
|
@ -0,0 +1,30 @@
|
|||
---
|
||||
title: CC32XX I2C
|
||||
id: ti,cc32xx-i2c
|
||||
|
||||
description: >
|
||||
This binding gives a base representation of the TI CC32XX I2C controller
|
||||
|
||||
inherits:
|
||||
!include i2c.yaml
|
||||
|
||||
properties:
|
||||
compatible:
|
||||
type: string
|
||||
category: required
|
||||
description: compatible strings
|
||||
constraint: "ti,cc32xx-i2c"
|
||||
|
||||
reg:
|
||||
type: int
|
||||
description: mmio register space
|
||||
generation: define
|
||||
category: required
|
||||
|
||||
interrupts:
|
||||
type: compound
|
||||
category: required
|
||||
description: required interrupts
|
||||
generation: define
|
||||
|
||||
...
|
Loading…
Add table
Add a link
Reference in a new issue