mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
Pico rp2350updates for I2C (#14440)
This commit is contained in:
parent
7722e728f3
commit
422fd7e3e8
11 changed files with 105 additions and 51 deletions
|
@ -1843,6 +1843,10 @@ const clivalue_t valueTable[] = {
|
|||
{ "gyro_2_align_yaw", VAR_INT16 | HARDWARE_VALUE, .config.minmax = { -3600, 3600 }, PG_GYRO_DEVICE_CONFIG, PG_ARRAY_ELEMENT_OFFSET(gyroDeviceConfig_t, 1, customAlignment.yaw) },
|
||||
#endif
|
||||
#ifdef I2C_FULL_RECONFIGURABILITY
|
||||
#ifdef USE_I2C_DEVICE_0
|
||||
{ "i2c0_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 0, pullUp) },
|
||||
{ "i2c0_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 0, clockSpeed) },
|
||||
#endif
|
||||
#ifdef USE_I2C_DEVICE_1
|
||||
{ "i2c1_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 0, pullUp) },
|
||||
{ "i2c1_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 0, clockSpeed) },
|
||||
|
|
|
@ -629,6 +629,9 @@ void init(void)
|
|||
// Note: Unlike UARTs which are configured when client is present,
|
||||
// I2C buses are initialized unconditionally if they are configured.
|
||||
|
||||
#ifdef USE_I2C_DEVICE_0
|
||||
i2cInit(I2CDEV_0);
|
||||
#endif
|
||||
#ifdef USE_I2C_DEVICE_1
|
||||
i2cInit(I2CDEV_1);
|
||||
#endif
|
||||
|
|
|
@ -41,6 +41,12 @@
|
|||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(i2cConfig_t, I2CDEV_COUNT, i2cConfig, PG_I2C_CONFIG, 1);
|
||||
|
||||
#ifndef I2C0_SCL_PIN
|
||||
#define I2C0_SCL_PIN NONE
|
||||
#endif
|
||||
#ifndef I2C0_SDA_PIN
|
||||
#define I2C0_SDA_PIN NONE
|
||||
#endif
|
||||
#ifndef I2C1_SCL_PIN
|
||||
#define I2C1_SCL_PIN NONE
|
||||
#endif
|
||||
|
@ -74,6 +80,9 @@ typedef struct i2cDefaultConfig_s {
|
|||
} i2cDefaultConfig_t;
|
||||
|
||||
static const i2cDefaultConfig_t i2cDefaultConfig[] = {
|
||||
#ifdef USE_I2C_DEVICE_0
|
||||
{ I2CDEV_0, IO_TAG(I2C0_SCL_PIN), IO_TAG(I2C0_SDA_PIN), I2C0_PULLUP, I2C0_CLOCKSPEED },
|
||||
#endif
|
||||
#ifdef USE_I2C_DEVICE_1
|
||||
{ I2CDEV_1, IO_TAG(I2C1_SCL_PIN), IO_TAG(I2C1_SDA_PIN), I2C1_PULLUP, I2C1_CLOCKSPEED },
|
||||
#endif
|
||||
|
|
|
@ -24,6 +24,9 @@
|
|||
#define DEBUG_MODE DEBUG_NONE
|
||||
#endif
|
||||
|
||||
#ifndef I2C0_CLOCKSPEED
|
||||
#define I2C0_CLOCKSPEED 800
|
||||
#endif
|
||||
#ifndef I2C1_CLOCKSPEED
|
||||
#define I2C1_CLOCKSPEED 800
|
||||
#endif
|
||||
|
@ -40,11 +43,13 @@
|
|||
// Default values for internal pullup
|
||||
|
||||
#if defined(USE_I2C_PULLUP)
|
||||
#define I2C0_PULLUP true
|
||||
#define I2C1_PULLUP true
|
||||
#define I2C2_PULLUP true
|
||||
#define I2C3_PULLUP true
|
||||
#define I2C4_PULLUP true
|
||||
#else
|
||||
#define I2C0_PULLUP false
|
||||
#define I2C1_PULLUP false
|
||||
#define I2C2_PULLUP false
|
||||
#define I2C3_PULLUP false
|
||||
|
|
|
@ -179,8 +179,8 @@ MCU_COMMON_SRC = \
|
|||
APM32/dma_apm32f4xx.c \
|
||||
APM32/serial_uart_apm32f4xx.c \
|
||||
drivers/adc.c \
|
||||
drivers/bus_i2c_config.c \
|
||||
drivers/bus_spi_config.c \
|
||||
common/stm32/bus_i2c_config.c \
|
||||
common/stm32/bus_spi_hw.c \
|
||||
common/stm32/bus_spi_pinconfig.c \
|
||||
common/stm32/serial_uart_hw.c \
|
||||
|
@ -217,8 +217,8 @@ SPEED_OPTIMISED_SRC += \
|
|||
SIZE_OPTIMISED_SRC += \
|
||||
APM32/usb/vcp/serial_usb_vcp.c \
|
||||
drivers/inverter.c \
|
||||
drivers/bus_i2c_config.c \
|
||||
drivers/bus_spi_config.c \
|
||||
common/stm32/bus_i2c_config.c \
|
||||
common/stm32/bus_spi_pinconfig.c \
|
||||
drivers/serial_escserial.c \
|
||||
drivers/serial_pinconfig.c \
|
||||
|
|
|
@ -121,8 +121,8 @@ MCU_COMMON_SRC = \
|
|||
drivers/bus_i2c_timing.c \
|
||||
drivers/usb_msc_common.c \
|
||||
drivers/adc.c \
|
||||
drivers/bus_i2c_config.c \
|
||||
drivers/bus_spi_config.c \
|
||||
common/stm32/bus_i2c_config.c \
|
||||
common/stm32/bus_spi_pinconfig.c \
|
||||
common/stm32/bus_spi_hw.c \
|
||||
common/stm32/serial_uart_hw.c \
|
||||
|
@ -144,8 +144,8 @@ SPEED_OPTIMISED_SRC += \
|
|||
SIZE_OPTIMISED_SRC += \
|
||||
drivers/bus_i2c_timing.c \
|
||||
drivers/inverter.c \
|
||||
drivers/bus_i2c_config.c \
|
||||
drivers/bus_spi_config.c \
|
||||
common/stm32/bus_i2c_config.c \
|
||||
common/stm32/bus_spi_pinconfig.c \
|
||||
drivers/serial_escserial.c \
|
||||
drivers/serial_pinconfig.c \
|
||||
|
|
|
@ -27,6 +27,8 @@
|
|||
|
||||
#if defined(USE_I2C) && !defined(SOFT_I2C)
|
||||
|
||||
#include "pg/bus_i2c.h"
|
||||
|
||||
#include "hardware/i2c.h"
|
||||
#include "hardware/dma.h"
|
||||
#include "hardware/irq.h"
|
||||
|
@ -44,43 +46,59 @@ i2cDevice_t i2cDevice[I2CDEV_COUNT];
|
|||
|
||||
const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
|
||||
#ifdef USE_I2C_DEVICE_0
|
||||
{
|
||||
{
|
||||
.device = I2CDEV_0,
|
||||
.reg = I2C0,
|
||||
.sclPins = {
|
||||
{ DEFIO_TAG_E(PA1) },
|
||||
{ DEFIO_TAG_E(PA5) },
|
||||
{ DEFIO_TAG_E(PA9) },
|
||||
{ DEFIO_TAG_E(PA13) },
|
||||
},
|
||||
.sdaPins = {
|
||||
{ DEFIO_TAG_E(PA0) },
|
||||
{ DEFIO_TAG_E(PA4) },
|
||||
{ DEFIO_TAG_E(PA8) },
|
||||
{ DEFIO_TAG_E(PA12) },
|
||||
},
|
||||
.reg = i2c0,
|
||||
},
|
||||
#endif
|
||||
#ifdef USE_I2C_DEVICE_1
|
||||
{
|
||||
.device = I2CDEV_1,
|
||||
.reg = I2C1,
|
||||
.sclPins = {
|
||||
{ DEFIO_TAG_E(PA3) },
|
||||
{ DEFIO_TAG_E(PA7) },
|
||||
{ DEFIO_TAG_E(PA11) },
|
||||
{ DEFIO_TAG_E(PA15) },
|
||||
},
|
||||
.sdaPins = {
|
||||
{ DEFIO_TAG_E(PA2) },
|
||||
{ DEFIO_TAG_E(PA6) },
|
||||
{ DEFIO_TAG_E(PA10) },
|
||||
{ DEFIO_TAG_E(PA14) },
|
||||
}
|
||||
.reg = i2c1,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
void i2cHardwareConfigure(const i2cConfig_t *i2cConfig)
|
||||
{
|
||||
for (int index = 0 ; index < I2CDEV_COUNT ; index++) {
|
||||
const i2cHardware_t *hardware = &i2cHardware[index];
|
||||
|
||||
if (!hardware->reg) {
|
||||
continue;
|
||||
}
|
||||
|
||||
I2CDevice device = hardware->device;
|
||||
i2cDevice_t *pDev = &i2cDevice[device];
|
||||
|
||||
memset(pDev, 0, sizeof(*pDev));
|
||||
IO_t confSclIO = IOGetByTag(i2cConfig[device].ioTagScl);
|
||||
IO_t confSdaIO = IOGetByTag(i2cConfig[device].ioTagSda);
|
||||
int confSclPin = IO_GPIOPinIdx(confSclIO);
|
||||
int confSdaPin = IO_GPIOPinIdx(confSdaIO);
|
||||
|
||||
#ifdef RP2350B
|
||||
uint16_t numPins = 48;
|
||||
#else
|
||||
uint16_t numPins = 30;
|
||||
#endif
|
||||
|
||||
// I2C0 on pins 0,1 mod 4, I2C1 on pins 2,3 mod 4
|
||||
// SDA on pins 0 mod 2, SCL on pins 1 mod 2
|
||||
int pinOffset = device == I2CDEV_0 ? 0 : 2;
|
||||
if (confSdaPin >= 0 && confSclPin >= 0 &&
|
||||
confSdaPin < numPins && confSclPin < numPins &&
|
||||
(confSdaPin % 4) == pinOffset && (confSclPin % 4) == (pinOffset + 1)) {
|
||||
pDev->scl = confSclIO;
|
||||
pDev->sda = confSdaIO;
|
||||
pDev->hardware = hardware;
|
||||
pDev->reg = hardware->reg;
|
||||
pDev->pullUp = i2cConfig[device].pullUp;
|
||||
pDev->clockSpeed = i2cConfig[device].clockSpeed;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static bool i2cHandleHardwareFailure(I2CDevice device)
|
||||
{
|
||||
UNUSED(device);
|
||||
|
@ -105,7 +123,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_,
|
|||
return false;
|
||||
}
|
||||
|
||||
i2c_inst_t *port = I2C_INST(&i2cHardware[device].reg);
|
||||
i2c_inst_t *port = I2C_INST(i2cHardware[device].reg);
|
||||
|
||||
if (!port) {
|
||||
return false;
|
||||
|
@ -117,7 +135,8 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_,
|
|||
|
||||
uint8_t buf[I2C_TX_BUFFER_LENGTH] = { reg_, 0 };
|
||||
memcpy(&buf[1], data, len_);
|
||||
int status = i2c_write_timeout_us(port, addr_ << 1, buf, len_ + 1, true, I2C_TIMEOUT_US);
|
||||
bool nostop = false;
|
||||
int status = i2c_write_timeout_us(port, addr_, buf, len_ + 1, nostop, I2C_TIMEOUT_US);
|
||||
|
||||
if (status < 0) {
|
||||
return i2cHandleHardwareFailure(device);
|
||||
|
@ -132,18 +151,20 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t
|
|||
return false;
|
||||
}
|
||||
|
||||
i2c_inst_t *port = I2C_INST(&i2cHardware[device].reg);
|
||||
i2c_inst_t *port = I2C_INST(i2cHardware[device].reg);
|
||||
|
||||
if (!port) {
|
||||
return false;
|
||||
}
|
||||
|
||||
int status = i2c_write_timeout_us(port, addr_ << 1, ®_, 1, true, I2C_TIMEOUT_US);
|
||||
bool nostop = true;
|
||||
int status = i2c_write_timeout_us(port, addr_, ®_, 1, nostop, I2C_TIMEOUT_US);
|
||||
if (status < 0) {
|
||||
return i2cHandleHardwareFailure(device);
|
||||
}
|
||||
|
||||
status = i2c_read_timeout_us(port, addr_ << 1, buf, len, true, I2C_TIMEOUT_US);
|
||||
nostop = false;
|
||||
status = i2c_read_timeout_us(port, addr_, buf, len, nostop, I2C_TIMEOUT_US);
|
||||
if (status < 0) {
|
||||
return i2cHandleHardwareFailure(device);
|
||||
}
|
||||
|
@ -154,6 +175,7 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t
|
|||
bool i2cReadBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
|
||||
{
|
||||
// TODO: Implement genuine non-blocking read using DMA or similar mechanism
|
||||
// ( I2C0_IRQ, I2C1_IRQ ...)
|
||||
return i2cRead(device, addr_, reg_, len, buf);
|
||||
}
|
||||
|
||||
|
@ -163,7 +185,7 @@ bool i2cBusy(I2CDevice device, bool *error)
|
|||
return false;
|
||||
}
|
||||
|
||||
i2c_inst_t *port = I2C_INST(&i2cHardware[device].reg);
|
||||
i2c_inst_t *port = I2C_INST(i2cHardware[device].reg);
|
||||
|
||||
if (!port) {
|
||||
return false;
|
||||
|
@ -173,11 +195,14 @@ bool i2cBusy(I2CDevice device, bool *error)
|
|||
*error = 0;
|
||||
}
|
||||
|
||||
// TODO check: If we are using DMA (for a sequence of transfers?), then we will need to
|
||||
// protect against that being in progress
|
||||
|
||||
// Read the IC_STATUS register
|
||||
uint32_t status_reg = port->hw->status;
|
||||
|
||||
// The bit for MST_ACTIVITY is (1 << 5).
|
||||
return (status_reg & (1 << 5)) != 0;
|
||||
// The bit for (combined master/slave) ACTIVITY is (1 << 0).
|
||||
return (status_reg & (1 << 0)) != 0;
|
||||
}
|
||||
|
||||
void i2cInit(I2CDevice device)
|
||||
|
@ -189,22 +214,30 @@ void i2cInit(I2CDevice device)
|
|||
i2cDevice_t *pDev = &i2cDevice[device];
|
||||
|
||||
const i2cHardware_t *hardware = pDev->hardware;
|
||||
|
||||
const IO_t scl = pDev->scl;
|
||||
const IO_t sda = pDev->sda;
|
||||
const uint8_t sclPin = IO_Pin(scl);
|
||||
const uint8_t sdaPin = IO_Pin(sda);
|
||||
|
||||
if (!hardware || IOGetOwner(scl) || IOGetOwner(sda)) {
|
||||
if (!hardware || !scl || !sda) {
|
||||
return;
|
||||
}
|
||||
|
||||
i2c_init(I2C_INST(hardware->reg), pDev->clockSpeed);
|
||||
// Set owners
|
||||
IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
|
||||
IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));
|
||||
|
||||
// Initialise device
|
||||
i2c_init(I2C_INST(hardware->reg), 1000 * pDev->clockSpeed);
|
||||
|
||||
// Set up GPIO pins for I2C
|
||||
gpio_set_function(IO_Pin(sda), GPIO_FUNC_I2C);
|
||||
gpio_set_function(IO_Pin(scl), GPIO_FUNC_I2C);
|
||||
gpio_set_function(sdaPin, GPIO_FUNC_I2C);
|
||||
gpio_set_function(sclPin, GPIO_FUNC_I2C);
|
||||
|
||||
// Enable internal pull-up resistors
|
||||
gpio_pull_up(IO_Pin(sda));
|
||||
gpio_pull_up(IO_Pin(scl));
|
||||
gpio_pull_up(sdaPin);
|
||||
gpio_pull_up(sclPin);
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif // #if defined(USE_I2C) && !defined(SOFT_I2C)
|
||||
|
|
|
@ -25,6 +25,7 @@
|
|||
|
||||
#include "pico.h"
|
||||
#include "pico/stdlib.h"
|
||||
#include "hardware/i2c.h"
|
||||
#include "hardware/spi.h"
|
||||
#include "hardware/dma.h"
|
||||
#include "hardware/flash.h"
|
||||
|
@ -37,8 +38,8 @@
|
|||
|
||||
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||
|
||||
#define I2C_TypeDef I2C0_Type
|
||||
#define I2C_INST(i2c) ((i2c_inst_t *)(i2c))
|
||||
#define I2C_TypeDef i2c_inst_t
|
||||
#define I2C_INST(i2c) (i2c)
|
||||
|
||||
#define GPIO_TypeDef io_bank0_hw_t
|
||||
//#define GPIO_InitTypeDef
|
||||
|
|
|
@ -376,7 +376,6 @@ MCU_COMMON_SRC = \
|
|||
drivers/inverter.c \
|
||||
drivers/bus_spi.c \
|
||||
drivers/bus_spi_config.c \
|
||||
drivers/bus_i2c_config.c \
|
||||
drivers/bus_i2c_utils.c \
|
||||
drivers/serial_pinconfig.c \
|
||||
drivers/serial_uart_pinconfig.c \
|
||||
|
|
|
@ -5,8 +5,8 @@ MCU_COMMON_SRC += \
|
|||
common/stm32/system.c \
|
||||
common/stm32/config_flash.c \
|
||||
common/stm32/bus_spi_pinconfig.c \
|
||||
drivers/bus_i2c_config.c \
|
||||
drivers/bus_spi_config.c \
|
||||
common/stm32/bus_i2c_config.c \
|
||||
common/stm32/bus_spi_hw.c \
|
||||
common/stm32/io_impl.c \
|
||||
common/stm32/serial_uart_hw.c \
|
||||
|
@ -16,8 +16,8 @@ MCU_COMMON_SRC += \
|
|||
common/stm32/dshot_bitbang_shared.c
|
||||
|
||||
SIZE_OPTIMISED_SRC += \
|
||||
drivers/bus_i2c_config.c \
|
||||
drivers/bus_spi_config.c \
|
||||
common/stm32/bus_i2c_config.c \
|
||||
common/stm32/config_flash.c \
|
||||
common/stm32/bus_spi_pinconfig.c
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue