1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2024-12-29 04:50:03 +01:00

Merge pull request #15624 from iosabi/qn908x_i2c

cpu/qn908x: Implement blocking I2C support
This commit is contained in:
benpicco 2020-12-20 00:49:39 +01:00 committed by GitHub
commit 674ed7104f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
11 changed files with 468 additions and 6 deletions

View File

@ -19,6 +19,7 @@ config BOARD_QN9080DK
select BOARD_HAS_XTAL_32M
select HAS_PERIPH_TIMER
select HAS_PERIPH_UART
select HAS_PERIPH_I2C
select HAS_PERIPH_UART_MODECFG
source "$(RIOTBOARD)/common/qn908x/Kconfig"

View File

@ -1,3 +1,4 @@
ifneq (,$(filter saul_default,$(USEMODULE)))
USEMODULE += saul_gpio
USEMODULE += mma8x5x
endif

View File

@ -3,6 +3,7 @@ CPU_MODEL = qn9080xhn
# Put defined MCU peripherals here (in alphabetical order)
FEATURES_PROVIDED += periph_gpio periph_gpio_irq
FEATURES_PROVIDED += periph_i2c
FEATURES_PROVIDED += periph_timer
FEATURES_PROVIDED += periph_uart periph_uart_modecfg

View File

@ -56,6 +56,18 @@ extern "C" {
#define BTN2_MODE GPIO_IN_PU
/** @} */
/**
* @name MMA8652FC 3-axis accelerometer bus configuration
*
* The MMA8652FC in the QN9080DK is only available when JP11 is shorted (the
* factory default).
* @{
*/
#define MMA8X5X_PARAM_I2C I2C_DEV(0)
#define MMA8X5X_PARAM_ADDR 0x1D
#define MMA8X5X_PARAM_TYPE (MMA8X5X_TYPE_MMA8652)
/** @} */
/**
* @brief Initialize board specific hardware
*/

View File

@ -28,6 +28,21 @@
extern "C" {
#endif
/**
* @name I2C configuration
* @{
*/
static const i2c_conf_t i2c_config[] = {
{
.dev = I2C1,
.pin_scl = GPIO_PIN(PORT_A, 6),
.pin_sda = GPIO_PIN(PORT_A, 7),
.speed = I2C_SPEED_FAST,
},
};
#define I2C_NUMOF ARRAY_SIZE(i2c_config)
/** @} */
/**
* @name UART configuration
* @{
@ -54,7 +69,6 @@ static const uart_conf_t uart_config[] = {
- Available clocks
- PWMs
- SPIs
- I2C
- ADC
- RTC
- RTT

View File

@ -13,6 +13,7 @@ config CPU_FAM_QN908X
select HAS_PERIPH_CPUID
select HAS_PERIPH_GPIO
select HAS_PERIPH_GPIO_IRQ
select HAS_PERIPH_I2C_RECONFIGURE
select HAS_PERIPH_RTC
select HAS_PERIPH_WDT
select HAS_PERIPH_WDT_CB

View File

@ -10,7 +10,7 @@ USEMODULE += vendor_fsl_clock
# All peripherals use gpio_mux.h
USEMODULE += periph_gpio_mux
ifneq (,$(filter periph_uart,$(USEMODULE)))
ifneq (,$(filter periph_uart periph_i2c,$(USEMODULE)))
USEMODULE += periph_flexcomm
endif

View File

@ -4,6 +4,7 @@ CPU_FAM = qn908x
FEATURES_PROVIDED += cortexm_mpu
FEATURES_PROVIDED += periph_cpuid
FEATURES_PROVIDED += periph_gpio periph_gpio_irq
FEATURES_PROVIDED += periph_i2c_reconfigure
FEATURES_PROVIDED += periph_rtc
FEATURES_PROVIDED += periph_wdt periph_wdt_cb

View File

@ -31,6 +31,35 @@ The GPIO driver uses the @ref GPIO_PIN(port, pin) macro to declare pins.
No configuration is necessary.
@defgroup cpu_qn908x_i2c NXP QN908x I2C
@ingroup cpu_qn908x
@brief NXP QN908x I2C driver
There are several FLEXCOMM interfaces in this chip, but only two of these
support I2C (FLEXCOMM1 and FLEXCOMM2) which are mapped as I2C0 and I2C1,
respectively. A single FLEXCOMM interface can only be used for one of the I2C,
UART or SPI interfaces, so for example USART1 and I2C0 can't be used at the
same time since they are both the same FLEXCOMM1 interface.
### I2C configuration example (for periph_conf.h) ###
static const i2c_conf_t i2c_config[] = {
{
.dev = I2C0,
.pin_scl = GPIO_PIN(PORT_A, 6), // or A8, A12, A20
.pin_sda = GPIO_PIN(PORT_A, 7), // or A9, A13, A21
.speed = I2C_SPEED_FAST,
},
{
.dev = I2C1,
.pin_scl = GPIO_PIN(PORT_A, 2), // or A5, A23, A27
.pin_sda = GPIO_PIN(PORT_A, 3), // or A4, A22, A26
.speed = I2C_SPEED_FAST,
},
};
#define I2C_NUMOF ARRAY_SIZE(i2c_config)
@defgroup cpu_qn908x_timer NXP QN908x Standard counter/timers (CTIMER)
@ingroup cpu_qn908x
@brief NXP QN908x timer driver
@ -85,13 +114,13 @@ other pin can be set to GPIO_UNDEF.
static const uart_conf_t uart_config[] = {
{
.dev = USART0,
.rx_pin = GPIO_PIN(PORT_A, 17), /* or 5 */
.tx_pin = GPIO_PIN(PORT_A, 16), /* or 4 */
.rx_pin = GPIO_PIN(PORT_A, 17), // or A5
.tx_pin = GPIO_PIN(PORT_A, 16), // or A4
},
{
.dev = USART1,
.rx_pin = GPIO_PIN(PORT_A, 9), /* or 13 */
.tx_pin = GPIO_PIN(PORT_A, 8), /* or 12 */
.rx_pin = GPIO_PIN(PORT_A, 9), // or A13
.tx_pin = GPIO_PIN(PORT_A, 8), // or A12
},
};
#define UART_NUMOF ARRAY_SIZE(uart_config)

View File

@ -149,6 +149,51 @@ enum {
#define TIMER_MAX_VALUE (0xffffffff)
/** @} */
/**
* @brief I2C bus speed values in kbit/s.
*
* @note We support arbitrary speed values up to 400 kbit/s.
*
* @{
*/
#define HAVE_I2C_SPEED_T
typedef enum {
I2C_SPEED_LOW = 10000u, /**< low speed mode: ~10 kbit/s */
I2C_SPEED_NORMAL = 100000u, /**< normal mode: ~100 kbit/s */
I2C_SPEED_FAST = 400000u, /**< fast mode: ~400 kbit/s */
I2C_SPEED_FAST_PLUS = 400000u, /**< not supported, capped at 400 kbit/s */
I2C_SPEED_HIGH = 400000u, /**< not supported, capped at 400 kbit/s */
} i2c_speed_t;
/** @} */
/**
* @brief I2C configuration options
*/
typedef struct {
I2C_Type *dev; /**< hardware device */
gpio_t pin_scl; /**< SCL pin */
gpio_t pin_sda; /**< SDA pin */
uint32_t speed; /**< bus speed in bit/s */
} i2c_conf_t;
/**
* @name Use shared I2C functions
* @{
*/
#define PERIPH_I2C_NEED_READ_REG
#define PERIPH_I2C_NEED_READ_REGS
#define PERIPH_I2C_NEED_WRITE_REG
#define PERIPH_I2C_NEED_WRITE_REGS
/** @} */
/**
* @name Define macros for sda and scl pins.
* @{
*/
#define i2c_pin_sda(dev) i2c_config[dev].pin_sda
#define i2c_pin_scl(dev) i2c_config[dev].pin_scl
/** @} */
/**
* @brief UART module configuration options
*

357
cpu/qn908x/periph/i2c.c Normal file
View File

@ -0,0 +1,357 @@
/*
* Copyright (C) 2020 iosabi
*
* This file is subject to the terms and conditions of the GNU Lesser General
* Public License v2.1. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu_qn908x
* @ingroup drivers_periph_i2c
*
* @{
*
* @file
* @brief Low-level I2C driver implementation
*
* @author iosabi <iosabi@protonmail.com>
*
* @}
*/
#include <assert.h>
#include <errno.h>
#include <stdint.h>
#include <stdlib.h>
#include "cpu.h"
#include "mutex.h"
#include "periph_conf.h"
#include "periph/i2c.h"
#include "vendor/drivers/fsl_clock.h"
#include "gpio_mux.h"
#include "flexcomm.h"
#define ENABLE_DEBUG 0
#include "debug.h"
static mutex_t locks[I2C_NUMOF];
/**
* @brief Limit value I2C CLKDIV register.
*/
#define I2C_CLKDIV_MAX 0xffffu
/**
* @brief Set the I2C controller mode clock speed.
*/
static void _i2c_controller_set_speed(I2C_Type *i2c_dev, uint32_t speed_hz)
{
/* The I2C clock source is based on the FLEXCOMM clock with the following
* formula:
* i2c freq := flexcomm freq / ((CLKDIV + 1) * (MSTTIME + 2) * 2)
* Where MSTTIME is a number between 0 and 7, and CLKDIV is between 0 and
* 0xffff.
* The MSTTIME register controls for how many cycles does the clock stay
* low and high, allowing to use different values for each one but we only
* use symmetric ones here, which is why there's a * 2 in the formula above.
*/
assert(speed_hz > 0);
uint32_t bus_freq = CLOCK_GetFreq(kCLOCK_BusClk);
uint32_t target = bus_freq / (2 * speed_hz);
uint32_t best_error = UINT_MAX;
uint32_t best_clkdiv = 0;
uint32_t best_msttime = 0;
for (uint32_t msttime_p2 = 9; msttime_p2 >= 2; msttime_p2--) {
uint32_t clkdiv_p1 = (target + msttime_p2 / 2) / msttime_p2;
if (clkdiv_p1 >= I2C_CLKDIV_MAX + 1) {
clkdiv_p1 = I2C_CLKDIV_MAX + 1;
}
uint32_t error =
abs((int32_t)target - (int32_t)(clkdiv_p1 * msttime_p2));
if (error < best_error) {
best_error = error;
best_clkdiv = clkdiv_p1 - 1;
best_msttime = msttime_p2 - 2;
}
}
i2c_dev->CLKDIV = I2C_CLKDIV_DIVVAL(best_clkdiv);
i2c_dev->MSTTIME = I2C_MSTTIME_MSTSCLLOW(best_msttime) |
I2C_MSTTIME_MSTSCLHIGH(best_msttime);
DEBUG("[i2c]: bus_fq=%" PRIu32" target_freq=%" PRIu32" msttime=%" PRIu32
" clkdiv=%" PRIu32 " error=%" PRIu32 "\n",
bus_freq, speed_hz, best_msttime, best_clkdiv, best_error);
}
static void _i2c_init_pins(i2c_t dev)
{
const i2c_conf_t *conf = &i2c_config[dev];
/* Configure SDA and SCL pins, the function value depends on the pin:
* FUNC4: A6, A7, A8, A9, A12, A13, A22, A23, A26, A27
* FUNC5: A2, A3, A4, A5, A20, A21
*/
static const uint32_t func5_mask =
(1 << 2) | (1 << 3) | (1 << 4) | (1 << 5) | (1 << 20) | (1 << 21);
/* TODO: Have a way to configure IOCON_MODE_PULLUP and IOCON_DRIVE_HIGH
* from the board. */
gpio_init_mux(conf->pin_sda,
((1u << GPIO_T_PIN(conf->pin_sda)) & func5_mask) ? 5 : 4);
gpio_init_mux(conf->pin_scl,
((1u << GPIO_T_PIN(conf->pin_scl)) & func5_mask) ? 5 : 4);
mutex_unlock(&locks[dev]);
}
void i2c_init(i2c_t dev)
{
assert(dev < I2C_NUMOF);
const i2c_conf_t *conf = &i2c_config[dev];
I2C_Type *const i2c_dev = conf->dev;
int flexcomm_num = flexcomm_init((FLEXCOMM_Type *)i2c_dev, FLEXCOMM_ID_I2C);
assert(flexcomm_num >= 0);
if (flexcomm_num == 1) {
/* Disable the FLECOMM1 MULT1/DIV1 divisor. FLEXCOMM2 doesn't have a
* fractional divisor. This divides the clock by (1 + N / 256) where
* N is set to 0 here, so the fractional divisor only divides by one. */
CLOCK_SetClkDiv(kCLOCK_DivFrg1, 0u);
}
/* Enable controller mode, no timeout, no monitor, no clock stretching. */
i2c_dev->CFG = I2C_CFG_MSTEN_MASK;
_i2c_controller_set_speed(i2c_dev, conf->speed);
locks[dev] = (mutex_t)MUTEX_INIT_LOCKED;
/* This also unlocks the mutex. */
_i2c_init_pins(dev);
}
#ifdef MODULE_PERIPH_I2C_RECONFIGURE
void i2c_init_pins(i2c_t dev)
{
assert(dev < I2C_NUMOF);
i2c_config[dev].dev->CFG |= I2C_CFG_MSTEN_MASK;
_i2c_init_pins(dev);
}
void i2c_deinit_pins(i2c_t dev)
{
assert(dev < I2C_NUMOF);
const i2c_conf_t *conf = &i2c_config[dev];
mutex_lock(&locks[dev]);
conf->dev->CFG &= ~I2C_CFG_MSTEN_MASK;
gpio_init_mux(conf->pin_sda, 0);
gpio_init_mux(conf->pin_scl, 0);
}
#endif /* MODULE_PERIPH_I2C_RECONFIGURE */
int i2c_acquire(i2c_t dev)
{
assert(dev < I2C_NUMOF);
mutex_lock(&locks[dev]);
return 0;
}
void i2c_release(i2c_t dev)
{
assert(dev < I2C_NUMOF);
mutex_unlock(&locks[dev]);
}
static uint32_t _i2c_wait_idle(I2C_Type *i2c_dev)
{
uint32_t status;
do {
status = i2c_dev->STAT;
} while ((status & I2C_STAT_MSTPENDING_MASK) == 0);
i2c_dev->STAT = I2C_STAT_MSTARBLOSS_MASK | I2C_STAT_MSTSTSTPERR_MASK;
return status;
}
static void _i2c_start(I2C_Type *i2c_dev, uint8_t addr_dir)
{
_i2c_wait_idle(i2c_dev);
i2c_dev->MSTDAT = addr_dir;
i2c_dev->MSTCTL = I2C_MSTCTL_MSTSTART_MASK; /* start */
}
static uint32_t _i2c_stop(I2C_Type *i2c_dev)
{
uint32_t status = _i2c_wait_idle(i2c_dev);
i2c_dev->MSTCTL = I2C_MSTCTL_MSTSTOP_MASK; /* stop */
return status;
}
/* Definitions for MSTSTATE bits in I2C Status register STAT */
/* Controller Idle State Code */
#define I2C_STAT_MSTSTATE_IDLE (0)
/* Controller Receive Ready State Code */
#define I2C_STAT_MSTSTATE_RXREADY (1)
/* Controller Transmit Ready State Code */
#define I2C_STAT_MSTSTATE_TXREADY (2)
/* Controller NACK by peripheral on address State Code */
#define I2C_STAT_MSTSTATE_NACKADR (3)
/* Controller NACK by peripheral on data State Code */
#define I2C_STAT_MSTSTATE_NACKDAT (4)
static int _i2c_transfer_blocking(i2c_t dev, uint32_t addr_dir, uint8_t *data,
size_t len, uint8_t flags)
{
assert((data != NULL) || (len == 0));
I2C_Type *i2c_dev = i2c_config[dev].dev;
uint32_t status = 0;
uint32_t controller_state;
if ((flags & I2C_NOSTART) == 0) {
if ((flags & I2C_ADDR10) != 0) {
_i2c_start(i2c_dev,
0xf0 | (addr_dir & 1) | ((addr_dir >> 8) & 0x6));
/* The second call to start sends a repeated start */
_i2c_start(i2c_dev, (addr_dir >> 1) & 0xff);
}
else {
_i2c_start(i2c_dev, addr_dir);
}
}
while (len) {
status = _i2c_wait_idle(i2c_dev);
if (status & (I2C_STAT_MSTARBLOSS_MASK | I2C_STAT_MSTSTSTPERR_MASK)) {
break;
}
controller_state = (status & I2C_STAT_MSTSTATE_MASK) >>
I2C_STAT_MSTSTATE_SHIFT;
switch (controller_state) {
case I2C_STAT_MSTSTATE_TXREADY:
/* I2C write case. */
if ((addr_dir & 1) != 0) {
/* This means that the direction requested in the transfer
* was to read, without a start condition and following
* a previous request to write, so the block is ready to
* write but we should be reading. */
_i2c_stop(i2c_dev);
return -EINVAL;
}
i2c_dev->MSTDAT = *(data++);
len--;
i2c_dev->MSTCTL = I2C_MSTCTL_MSTCONTINUE_MASK;
break;
case I2C_STAT_MSTSTATE_RXREADY:
/* I2C read case. */
if ((addr_dir & 1) != 1) {
/* Analog to the write case, we should be trying to writing
* in this case. */
i2c_dev->MSTDAT;
_i2c_stop(i2c_dev);
return -EINVAL;
}
*(data++) = i2c_dev->MSTDAT;
if (--len) {
i2c_dev->MSTCTL = I2C_MSTCTL_MSTCONTINUE_MASK;
}
else {
if ((flags & I2C_NOSTOP) == 0) {
/* initiate NAK and stop */
i2c_dev->MSTCTL = I2C_MSTCTL_MSTSTOP_MASK;
status = _i2c_wait_idle(i2c_dev);
}
}
break;
case I2C_STAT_MSTSTATE_NACKADR:
/* NACK on the address means no device. */
i2c_dev->MSTCTL = I2C_MSTCTL_MSTSTOP_MASK;
return -ENXIO;
case I2C_STAT_MSTSTATE_NACKDAT:
/* NACK on the data means that the device didn't ACK the last
* byte. */
i2c_dev->MSTCTL = I2C_MSTCTL_MSTSTOP_MASK;
return -EIO;
default:
return -EINVAL;
}
}
/* In the write case we didn't send a stop condition yet. */
if ((flags & I2C_NOSTOP) == 0 && (addr_dir & 1) == 0) {
status = _i2c_stop(i2c_dev);
/* The status will contain the last ACK/NACK */
controller_state = (status & I2C_STAT_MSTSTATE_MASK) >>
I2C_STAT_MSTSTATE_SHIFT;
if (controller_state == I2C_STAT_MSTSTATE_NACKDAT) {
return -EIO;
}
}
if (status & I2C_STAT_MSTARBLOSS_MASK) {
DEBUG("[i2c] Controller arbitration loss error flag, status 0x%.2"
PRIx32 "\n", status);
return -EAGAIN;
}
if (status & I2C_STAT_MSTSTSTPERR_MASK) {
/* Controller start/stop error flag. */
DEBUG("[i2c] Controller start/stop error flag\n");
return -EINVAL;
}
return 0;
}
#define I2C_ADDR_READ(addr) (((uint32_t)(addr) << 1u) | 1u)
#define I2C_ADDR_WRITE(addr) ((uint32_t)(addr) << 1u)
int i2c_read_bytes(i2c_t dev, uint16_t addr, void *data,
size_t len, uint8_t flags)
{
DEBUG("[i2c] R a=%.2x len=%2u f=%.2x, data:", addr, (unsigned)len, flags);
int ret =
_i2c_transfer_blocking(dev, I2C_ADDR_READ(addr), data, len, flags);
#if ENABLE_DEBUG
for (size_t i = 0; i < len; i++) {
DEBUG(" %.2x", ((uint8_t *)data)[i]);
}
DEBUG(", ret=%d\n", ret);
#endif
return ret;
}
int i2c_write_bytes(i2c_t dev, uint16_t addr, const void *data, size_t len,
uint8_t flags)
{
/* The write transfer should technically only use a const uint8_t* buffer
* but we are re-using the same function to save on code here. It will not
* be written to in the I2C write case. */
#if ENABLE_DEBUG
DEBUG("[i2c] W a=%.2x len=%2u f=%.2x, data:", addr, (unsigned)len, flags);
for (size_t i = 0; i < len; i++) {
DEBUG(" %.2x", ((uint8_t *)data)[i]);
}
#endif
int ret = _i2c_transfer_blocking(
dev, I2C_ADDR_WRITE(addr), (uint8_t *)data, len, flags);
DEBUG(", ret=%d\n", ret);
return ret;
}
void isr_flexcomm_i2c(USART_Type *dev, uint32_t flexcomm_num)
{
// TODO: Set up async mode with interrupts.
(void)dev;
(void)flexcomm_num;
cortexm_isr_end();
}