diff --git a/boards/ambiq/apollo3_evb/apollo3_evb-pinctrl.dtsi b/boards/ambiq/apollo3_evb/apollo3_evb-pinctrl.dtsi index cfba01ba4dea6..25fda178797bf 100644 --- a/boards/ambiq/apollo3_evb/apollo3_evb-pinctrl.dtsi +++ b/boards/ambiq/apollo3_evb/apollo3_evb-pinctrl.dtsi @@ -148,4 +148,15 @@ ambiq,iom-num = <6>; }; }; + + bleif_default: bleif_default{ + group1 { + pinmux = , + , + , + , + , + ; + }; + }; }; diff --git a/boards/ambiq/apollo3_evb/apollo3_evb.dts b/boards/ambiq/apollo3_evb/apollo3_evb.dts index 97021e84f2717..f7f60a651b41d 100644 --- a/boards/ambiq/apollo3_evb/apollo3_evb.dts +++ b/boards/ambiq/apollo3_evb/apollo3_evb.dts @@ -84,6 +84,12 @@ }; }; +&bleif { + pinctrl-0 = <&bleif_default>; + pinctrl-names = "default"; + status = "okay"; +}; + &uart0 { current-speed = <115200>; pinctrl-0 = <&uart0_default>; diff --git a/boards/ambiq/apollo3p_evb/apollo3p_evb-pinctrl.dtsi b/boards/ambiq/apollo3p_evb/apollo3p_evb-pinctrl.dtsi index 5619b134ee9ea..2f0b4acd54240 100644 --- a/boards/ambiq/apollo3p_evb/apollo3p_evb-pinctrl.dtsi +++ b/boards/ambiq/apollo3p_evb/apollo3p_evb-pinctrl.dtsi @@ -193,4 +193,15 @@ ambiq,iom-num = <2>; }; }; + + bleif_default: bleif_default{ + group1 { + pinmux = , + , + , + , + , + ; + }; + }; }; diff --git a/boards/ambiq/apollo3p_evb/apollo3p_evb.dts b/boards/ambiq/apollo3p_evb/apollo3p_evb.dts index e510c52ad44b7..7fd492a4cf534 100644 --- a/boards/ambiq/apollo3p_evb/apollo3p_evb.dts +++ b/boards/ambiq/apollo3p_evb/apollo3p_evb.dts @@ -84,6 +84,12 @@ }; }; +&bleif { + pinctrl-0 = <&bleif_default>; + pinctrl-names = "default"; + status = "okay"; +}; + &uart0 { current-speed = <115200>; pinctrl-0 = <&uart0_default>; diff --git a/drivers/bluetooth/hci/Kconfig b/drivers/bluetooth/hci/Kconfig index ad1d9da2df2a6..3ae965d914d30 100644 --- a/drivers/bluetooth/hci/Kconfig +++ b/drivers/bluetooth/hci/Kconfig @@ -119,8 +119,8 @@ config BT_NO_DRIVER config BT_AMBIQ_HCI bool "AMBIQ BT HCI driver" select SPI - select GPIO - select CLOCK_CONTROL + select GPIO if SOC_SERIES_APOLLO4X + select CLOCK_CONTROL if SOC_SERIES_APOLLO4X select BT_HCI_SETUP help Supports Ambiq Bluetooth SoC using SPI as the communication protocol. diff --git a/drivers/bluetooth/hci/apollox_blue.c b/drivers/bluetooth/hci/apollox_blue.c index eff8d8fbd8125..a25af495bf6e1 100644 --- a/drivers/bluetooth/hci/apollox_blue.c +++ b/drivers/bluetooth/hci/apollox_blue.c @@ -25,8 +25,13 @@ LOG_MODULE_REGISTER(bt_apollox_driver); #include #include +#include #include "apollox_blue.h" +#if (CONFIG_SOC_SERIES_APOLLO4X) #include "am_devices_cooper.h" +#elif (CONFIG_SOC_SERIES_APOLLO3X) +#include "am_apollo3_bt_support.h" +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ #define HCI_SPI_NODE DT_COMPAT_GET_ANY_STATUS_OKAY(ambiq_bt_hci_spi) #define SPI_DEV_NODE DT_BUS(HCI_SPI_NODE) @@ -44,6 +49,7 @@ LOG_MODULE_REGISTER(bt_apollox_driver); #define SPI_MAX_RX_MSG_LEN 258 +#if (CONFIG_SOC_SERIES_APOLLO4X) static const struct gpio_dt_spec irq_gpio = GPIO_DT_SPEC_GET(HCI_SPI_NODE, irq_gpios); static const struct gpio_dt_spec rst_gpio = GPIO_DT_SPEC_GET(HCI_SPI_NODE, reset_gpios); static const struct gpio_dt_spec cs_gpio = GPIO_DT_SPEC_GET(SPI_DEV_NODE, cs_gpios); @@ -54,10 +60,19 @@ static struct gpio_callback clkreq_gpio_cb; static const struct device *clk32m_dev = DEVICE_DT_GET(CLK_32M_NODE); static const struct device *clk32k_dev = DEVICE_DT_GET(CLK_32K_NODE); +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ extern void bt_packet_irq_isr(const struct device *unused1, struct gpio_callback *unused2, uint32_t unused3); +void bt_apollo_rcv_isr_preprocess(void) +{ +#if (CONFIG_SOC_SERIES_APOLLO3X) + am_apollo3_bt_isr_pre(); +#endif /* CONFIG_SOC_SERIES_APOLLO3X */ +} + +#if (CONFIG_SOC_SERIES_APOLLO4X) static bool irq_pin_state(void) { int pin_state; @@ -117,10 +132,13 @@ static void bt_apollo_controller_reset(void) /* Give the controller some time to boot */ k_sleep(K_MSEC(500)); } +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ int bt_apollo_spi_send(uint8_t *data, uint16_t len, bt_spi_transceive_fun transceive) { - int ret; + int ret = -ENOTSUP; + +#if (CONFIG_SOC_SERIES_APOLLO4X) uint8_t command[1] = {SPI_WRITE}; uint8_t response[2] = {0, 0}; uint16_t fail_count = 0; @@ -139,18 +157,24 @@ int bt_apollo_spi_send(uint8_t *data, uint16_t len, bt_spi_transceive_fun transc break; } } while (fail_count++ < SPI_WRITE_TIMEOUT); +#elif (CONFIG_SOC_SERIES_APOLLO3X) + ret = transceive(data, len, NULL, 0); + if ((ret) && (ret != AM_HAL_BLE_STATUS_SPI_NOT_READY)) { + LOG_ERR("SPI write error %d", ret); + } +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ return ret; } int bt_apollo_spi_rcv(uint8_t *data, uint16_t *len, bt_spi_transceive_fun transceive) { - int ret; - uint8_t command[1] = {SPI_READ}; + int ret = -ENOTSUP; uint8_t response[2] = {0, 0}; uint16_t read_size = 0; do { +#if (CONFIG_SOC_SERIES_APOLLO4X) /* Skip if the IRQ pin is not in high state */ if (!irq_pin_state()) { ret = -1; @@ -158,10 +182,26 @@ int bt_apollo_spi_rcv(uint8_t *data, uint16_t *len, bt_spi_transceive_fun transc } /* Check the available packet bytes */ + uint8_t command[1] = {SPI_READ}; ret = transceive(command, 1, response, 2); if (ret) { break; } +#elif (CONFIG_SOC_SERIES_APOLLO3X) + /* Skip if the IRQ bit is not set */ + if (!BLEIFn(0)->BSTATUS_b.BLEIRQ) { + ret = -1; + break; + } + + /* Check the available packet bytes */ + ret = transceive(NULL, 0, response, 2); + if (ret) { + break; + } +#else + break; +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ /* Check if the read size is acceptable */ read_size = (uint16_t)(response[0] | response[1] << 8); @@ -186,6 +226,7 @@ int bt_apollo_spi_rcv(uint8_t *data, uint16_t *len, bt_spi_transceive_fun transc bool bt_apollo_vnd_rcv_ongoing(uint8_t *data, uint16_t len) { +#if (CONFIG_SOC_SERIES_APOLLO4X) /* The vendor specific handshake command/response is incompatible with * standard Bluetooth HCI format, need to handle the received packets * specifically. @@ -196,14 +237,18 @@ bool bt_apollo_vnd_rcv_ongoing(uint8_t *data, uint16_t len) } else { return false; } +#else + return false; +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ } int bt_hci_transport_setup(const struct device *dev) { ARG_UNUSED(dev); - int ret; + int ret = 0; +#if (CONFIG_SOC_SERIES_APOLLO4X) /* Configure the XO32MHz and XO32kHz clocks.*/ clock_control_configure(clk32k_dev, NULL, NULL); clock_control_configure(clk32m_dev, NULL, NULL); @@ -256,13 +301,18 @@ int bt_hci_transport_setup(const struct device *dev) /* Configure the interrupt edge for IRQ pin */ gpio_pin_interrupt_configure_dt(&irq_gpio, GPIO_INT_EDGE_RISING); +#elif (CONFIG_SOC_SERIES_APOLLO3X) + IRQ_CONNECT(DT_IRQN(SPI_DEV_NODE), DT_IRQ(SPI_DEV_NODE, priority), bt_packet_irq_isr, 0, 0); +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ - return 0; + return ret; } int bt_apollo_controller_init(spi_transmit_fun transmit) { - int ret; + int ret = 0; + +#if (CONFIG_SOC_SERIES_APOLLO4X) am_devices_cooper_callback_t cb = { .write = transmit, .reset = bt_apollo_controller_reset, @@ -277,10 +327,21 @@ int bt_apollo_controller_init(spi_transmit_fun transmit) am_devices_cooper_set_initialize_state(AM_DEVICES_COOPER_STATE_INITIALIZE_FAIL); LOG_ERR("BT controller initialization fail"); } +#elif (CONFIG_SOC_SERIES_APOLLO3X) + ret = am_apollo3_bt_controller_init(); + if (ret == AM_HAL_STATUS_SUCCESS) { + LOG_INF("BT controller initialized"); + } else { + LOG_ERR("BT controller initialization fail"); + } + + irq_enable(DT_IRQN(SPI_DEV_NODE)); +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ return ret; } +#if (CONFIG_SOC_SERIES_APOLLO4X) static int bt_apollo_set_nvds(void) { int ret; @@ -334,19 +395,23 @@ static int bt_apollo_set_nvds(void) return ret; } +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ int bt_apollo_vnd_setup(void) { - int ret; + int ret = 0; +#if (CONFIG_SOC_SERIES_APOLLO4X) /* Set the NVDS parameters to BLE controller */ ret = bt_apollo_set_nvds(); +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ return ret; } int bt_apollo_dev_init(void) { +#if (CONFIG_SOC_SERIES_APOLLO4X) if (!gpio_is_ready_dt(&irq_gpio)) { LOG_ERR("IRQ GPIO device not ready"); return -ENODEV; @@ -361,6 +426,7 @@ int bt_apollo_dev_init(void) LOG_ERR("CLKREQ GPIO device not ready"); return -ENODEV; } +#endif /* CONFIG_SOC_SERIES_APOLLO4X */ return 0; } diff --git a/drivers/bluetooth/hci/apollox_blue.h b/drivers/bluetooth/hci/apollox_blue.h index a05238657e5a5..85e586d790856 100644 --- a/drivers/bluetooth/hci/apollox_blue.h +++ b/drivers/bluetooth/hci/apollox_blue.h @@ -98,6 +98,12 @@ int bt_apollo_vnd_setup(void); */ bool bt_apollo_vnd_rcv_ongoing(uint8_t *data, uint16_t len); +/** + * @brief Do the specific preprocessing in HCI packet receiving ISR if needed, + * for example, clear the interrupt status. + */ +void bt_apollo_rcv_isr_preprocess(void); + #ifdef __cplusplus } #endif diff --git a/drivers/bluetooth/hci/hci_ambiq.c b/drivers/bluetooth/hci/hci_ambiq.c index ec3a0b944fe46..9428594980d66 100644 --- a/drivers/bluetooth/hci/hci_ambiq.c +++ b/drivers/bluetooth/hci/hci_ambiq.c @@ -29,17 +29,18 @@ LOG_MODULE_REGISTER(bt_hci_driver); #define PACKET_TYPE 0 #define PACKET_TYPE_SIZE 1 #define EVT_HEADER_TYPE 0 -#define EVT_HEADER_EVENT 1 -#define EVT_HEADER_SIZE 2 -#define EVT_VENDOR_CODE_LSB 3 -#define EVT_VENDOR_CODE_MSB 4 -#define CMD_OGF 1 -#define CMD_OCF 2 +#define EVT_CMD_COMP_OP_LSB 3 +#define EVT_CMD_COMP_OP_MSB 4 +#define EVT_CMD_COMP_DATA 5 #define EVT_OK 0 #define EVT_DISCARD 1 #define EVT_NOP 2 +#define BT_FEAT_SET_BIT(feat, octet, bit) (feat[octet] |= BIT(bit)) +#define BT_FEAT_SET_NO_BREDR(feat) BT_FEAT_SET_BIT(feat, 4, 5) +#define BT_FEAT_SET_LE(feat) BT_FEAT_SET_BIT(feat, 4, 6) + /* Max SPI buffer length for transceive operations. * The maximum TX packet number is 512 bytes data + 12 bytes header. * The maximum RX packet number is 255 bytes data + 3 header. @@ -47,6 +48,13 @@ LOG_MODULE_REGISTER(bt_hci_driver); #define SPI_MAX_TX_MSG_LEN 524 #define SPI_MAX_RX_MSG_LEN 258 +/* The controller may be unavailable to receive packets because it is busy + * on processing something or have packets to send to host. Need to free the + * SPI bus and wait some moment to try again. + */ +#define SPI_BUSY_WAIT_INTERVAL_MS 25 +#define SPI_BUSY_TX_ATTEMPTS 200 + static uint8_t __noinit rxmsg[SPI_MAX_RX_MSG_LEN]; static const struct device *spi_dev = DEVICE_DT_GET(SPI_DEV_NODE); static struct spi_config spi_cfg = { @@ -67,6 +75,7 @@ static K_SEM_DEFINE(sem_spi_available, 1, 1); void bt_packet_irq_isr(const struct device *unused1, struct gpio_callback *unused2, uint32_t unused3) { + bt_apollo_rcv_isr_preprocess(); k_sem_give(&sem_irq); } @@ -82,15 +91,27 @@ static inline int bt_spi_transceive(void *tx, uint32_t tx_len, void *rx, uint32_ static int spi_send_packet(uint8_t *data, uint16_t len) { int ret; + uint16_t fail_count = 0; - /* Wait for SPI bus to be available */ - k_sem_take(&sem_spi_available, K_FOREVER); + do { + /* Wait for SPI bus to be available */ + k_sem_take(&sem_spi_available, K_FOREVER); - /* Send the SPI packet to controller */ - ret = bt_apollo_spi_send(data, len, bt_spi_transceive); + /* Send the SPI packet to controller */ + ret = bt_apollo_spi_send(data, len, bt_spi_transceive); - /* Free the SPI bus */ - k_sem_give(&sem_spi_available); + /* Free the SPI bus */ + k_sem_give(&sem_spi_available); + + if (ret) { + /* Give some chance to controller to complete the processing or + * packets sending. + */ + k_sleep(K_MSEC(SPI_BUSY_WAIT_INTERVAL_MS)); + } else { + break; + } + } while (fail_count++ < SPI_BUSY_TX_ATTEMPTS); return ret; } @@ -113,7 +134,7 @@ static int spi_receive_packet(uint8_t *data, uint16_t *len) static int hci_event_filter(const uint8_t *evt_data) { - uint8_t evt_type = evt_data[0]; + uint8_t evt_type = evt_data[EVT_HEADER_TYPE]; switch (evt_type) { case BT_HCI_EVT_LE_META_EVENT: { @@ -127,11 +148,26 @@ static int hci_event_filter(const uint8_t *evt_data) } } case BT_HCI_EVT_CMD_COMPLETE: { - uint16_t opcode = (uint16_t)(evt_data[3] + (evt_data[4] << 8)); + uint16_t opcode = (uint16_t)(evt_data[EVT_CMD_COMP_OP_LSB] + + (evt_data[EVT_CMD_COMP_OP_MSB] << 8)); switch (opcode) { case BT_OP_NOP: return EVT_NOP; + case BT_HCI_OP_READ_LOCAL_FEATURES: { + /* The BLE controller of some Ambiq Apollox Blue SOC may have issue to + * report the expected supported features bitmask successfully, thought the + * features are actually supportive. Need to correct them before going to + * the host stack. + */ + struct bt_hci_rp_read_local_features *rp = + (void *)&evt_data[EVT_CMD_COMP_DATA]; + if (rp->status == 0) { + BT_FEAT_SET_NO_BREDR(rp->features); + BT_FEAT_SET_LE(rp->features); + } + return EVT_OK; + } default: return EVT_OK; } diff --git a/drivers/spi/CMakeLists.txt b/drivers/spi/CMakeLists.txt index 840c9dcdc5f6d..f7c8cc6fc791c 100644 --- a/drivers/spi/CMakeLists.txt +++ b/drivers/spi/CMakeLists.txt @@ -45,6 +45,7 @@ zephyr_library_sources_ifdef(CONFIG_SPI_SMARTBOND spi_smartbond.c) zephyr_library_sources_ifdef(CONFIG_SPI_OPENTITAN spi_opentitan.c) zephyr_library_sources_ifdef(CONFIG_SPI_NUMAKER spi_numaker.c) zephyr_library_sources_ifdef(CONFIG_SPI_AMBIQ spi_ambiq.c) +zephyr_library_sources_ifdef(CONFIG_SPI_AMBIQ_BLEIF spi_ambiq_bleif.c) zephyr_library_sources_ifdef(CONFIG_SPI_RPI_PICO_PIO spi_rpi_pico_pio.c) zephyr_library_sources_ifdef(CONFIG_MSPI_AMBIQ mspi_ambiq.c) zephyr_library_sources_ifdef(CONFIG_SPI_MCHP_MSS spi_mchp_mss.c) diff --git a/drivers/spi/Kconfig.ambiq b/drivers/spi/Kconfig.ambiq index 15eaf7463a46b..04113482f1be6 100644 --- a/drivers/spi/Kconfig.ambiq +++ b/drivers/spi/Kconfig.ambiq @@ -1,6 +1,7 @@ # Ambiq SDK SPI # # Copyright (c) 2023 Antmicro +# Copyright (c) 2024 Ambiq Micro Inc. # # SPDX-License-Identifier: Apache-2.0 # @@ -22,3 +23,28 @@ config MSPI_AMBIQ select AMBIQ_HAL_USE_MSPI help Enable driver for Ambiq MSPI. + +config SPI_AMBIQ_BLEIF + bool "AMBIQ SPI-BLEIF driver" + default y + depends on DT_HAS_AMBIQ_SPI_BLEIF_ENABLED + select AMBIQ_HAL + select AMBIQ_HAL_USE_BLEIF + help + Enable driver for Ambiq Apollox Blue SOC (e.g. Apollo3 Blue) + which uses internal designed BLEIF module (different from the + general IOM module) for SPI transceiver. It is always used for + the Bluetooth HCI communication. + +if SPI_AMBIQ_BLEIF + +config SPI_AMBIQ_BLEIF_TIMING_TRACE + bool "Ambiq SPI-BLEIF timing trace" + help + The pins for the SPI transceiver are not exposed from the chips + and no need for user to confiugre them. But the chips design the + configurable BLEIF timing observation functions on other exposed + pins. The user can enable it to configure the pins for timing + trace purpose. + +endif # SPI_AMBIQ_BLEIF diff --git a/drivers/spi/spi_ambiq_bleif.c b/drivers/spi/spi_ambiq_bleif.c new file mode 100644 index 0000000000000..ceaf598455ded --- /dev/null +++ b/drivers/spi/spi_ambiq_bleif.c @@ -0,0 +1,215 @@ +/* + * Copyright (c) 2024 Ambiq Micro Inc. + * + * SPDX-License-Identifier: Apache-2.0 + * + * Some Ambiq Apollox Blue SOC (e.g. Apollo3 Blue) uses internal designed BLEIF module which is + * different from the general IOM module for SPI transceiver. The called HAL API will also be + * independent. This driver is implemented for the BLEIF module usage scenarios. + */ + +#define DT_DRV_COMPAT ambiq_spi_bleif + +#include +LOG_MODULE_REGISTER(spi_ambiq_bleif); + +#include +#include +#include +#include +#include +#include +#include "spi_context.h" +#include + +#define PWRCTRL_MAX_WAIT_US 5 + +typedef int (*ambiq_spi_pwr_func_t)(void); + +struct spi_ambiq_config { + uint32_t base; + int size; + const struct pinctrl_dev_config *pcfg; + ambiq_spi_pwr_func_t pwr_func; +}; + +struct spi_ambiq_data { + struct spi_context ctx; + am_hal_ble_config_t ble_cfg; + void *BLEhandle; +}; + +#define SPI_BASE (((const struct spi_ambiq_config *)(dev)->config)->base) +#define REG_STAT 0x268 +#define SPI_STAT(dev) (SPI_BASE + REG_STAT) +#define SPI_WORD_SIZE 8 + +static int spi_config(const struct device *dev, const struct spi_config *config) +{ + struct spi_ambiq_data *data = dev->data; + struct spi_context *ctx = &(data->ctx); + + int ret = 0; + + if (spi_context_configured(ctx, config)) { + /* Already configured. No need to do it again. */ + return 0; + } + + if (SPI_WORD_SIZE_GET(config->operation) != SPI_WORD_SIZE) { + LOG_ERR("Word size must be %d", SPI_WORD_SIZE); + return -ENOTSUP; + } + + if ((config->operation & SPI_LINES_MASK) != SPI_LINES_SINGLE) { + LOG_ERR("Only supports single mode"); + return -ENOTSUP; + } + + if (config->operation & SPI_LOCK_ON) { + LOG_ERR("Lock On not supported"); + return -ENOTSUP; + } + + if (config->operation & SPI_TRANSFER_LSB) { + LOG_ERR("LSB first not supported"); + return -ENOTSUP; + } + + if (config->operation & SPI_OP_MODE_SLAVE) { + LOG_ERR("Slave mode not supported"); + return -ENOTSUP; + } + if (config->operation & SPI_MODE_LOOP) { + LOG_ERR("Loopback mode not supported"); + return -ENOTSUP; + } + + /* We consider only the default configuration defined in HAL is tested and stable. */ + data->ble_cfg = am_hal_ble_default_config; + + ctx->config = config; + + ret = am_hal_ble_config(data->BLEhandle, &data->ble_cfg); + + return ret; +} + +static int spi_ambiq_xfer(const struct device *dev, const struct spi_config *config) +{ + struct spi_ambiq_data *data = dev->data; + struct spi_context *ctx = &data->ctx; + int ret = 0; + + am_hal_ble_transfer_t trans = {0}; + + if (ctx->tx_len) { + trans.ui8Command = AM_HAL_BLE_WRITE; + trans.pui32Data = (uint32_t *)ctx->tx_buf; + trans.ui16Length = ctx->tx_len; + trans.bContinue = false; + } else { + trans.ui8Command = AM_HAL_BLE_READ; + trans.pui32Data = (uint32_t *)ctx->rx_buf; + trans.ui16Length = ctx->rx_len; + trans.bContinue = false; + } + + ret = am_hal_ble_blocking_transfer(data->BLEhandle, &trans); + spi_context_complete(ctx, dev, 0); + + return ret; +} + +static int spi_ambiq_transceive(const struct device *dev, const struct spi_config *config, + const struct spi_buf_set *tx_bufs, + const struct spi_buf_set *rx_bufs) +{ + struct spi_ambiq_data *data = dev->data; + int ret; + + ret = spi_config(dev, config); + + if (ret) { + return ret; + } + + if (!tx_bufs && !rx_bufs) { + return 0; + } + + spi_context_buffers_setup(&data->ctx, tx_bufs, rx_bufs, 1); + + ret = spi_ambiq_xfer(dev, config); + + return ret; +} + +static int spi_ambiq_release(const struct device *dev, const struct spi_config *config) +{ + struct spi_ambiq_data *data = dev->data; + + if (!sys_read32(SPI_STAT(dev))) { + return -EBUSY; + } + + spi_context_unlock_unconditionally(&data->ctx); + + return 0; +} + +static struct spi_driver_api spi_ambiq_driver_api = { + .transceive = spi_ambiq_transceive, + .release = spi_ambiq_release, +}; + +static int spi_ambiq_init(const struct device *dev) +{ + struct spi_ambiq_data *data = dev->data; + const struct spi_ambiq_config *cfg = dev->config; + int ret; + +#if defined(CONFIG_SPI_AMBIQ_BLEIF_TIMING_TRACE) + ret = pinctrl_apply_state(cfg->pcfg, PINCTRL_STATE_DEFAULT); + if (ret) { + return ret; + } +#endif /* CONFIG_SPI_AMBIQ_BLEIF_TIMING_TRACE */ + + ret = am_hal_ble_initialize((cfg->base - REG_BLEIF_BASEADDR) / cfg->size, &data->BLEhandle); + if (ret) { + return ret; + } + + ret = am_hal_ble_power_control(data->BLEhandle, AM_HAL_BLE_POWER_ACTIVE); + if (ret) { + return ret; + } + + ret = cfg->pwr_func(); + + return ret; +} + +#define AMBIQ_SPI_BLEIF_INIT(n) \ + PINCTRL_DT_INST_DEFINE(n); \ + static int pwr_on_ambiq_spi_##n(void) \ + { \ + uint32_t addr = DT_REG_ADDR(DT_INST_PHANDLE(n, ambiq_pwrcfg)) + \ + DT_INST_PHA(n, ambiq_pwrcfg, offset); \ + sys_write32((sys_read32(addr) | DT_INST_PHA(n, ambiq_pwrcfg, mask)), addr); \ + k_busy_wait(PWRCTRL_MAX_WAIT_US); \ + return 0; \ + } \ + static struct spi_ambiq_data spi_ambiq_data##n = { \ + SPI_CONTEXT_INIT_LOCK(spi_ambiq_data##n, ctx), \ + SPI_CONTEXT_INIT_SYNC(spi_ambiq_data##n, ctx)}; \ + static const struct spi_ambiq_config spi_ambiq_config##n = { \ + .base = DT_INST_REG_ADDR(n), \ + .size = DT_INST_REG_SIZE(n), \ + .pcfg = PINCTRL_DT_INST_DEV_CONFIG_GET(n), \ + .pwr_func = pwr_on_ambiq_spi_##n}; \ + DEVICE_DT_INST_DEFINE(n, spi_ambiq_init, NULL, &spi_ambiq_data##n, &spi_ambiq_config##n, \ + POST_KERNEL, CONFIG_SPI_INIT_PRIORITY, &spi_ambiq_driver_api); + +DT_INST_FOREACH_STATUS_OKAY(AMBIQ_SPI_BLEIF_INIT) diff --git a/dts/arm/ambiq/ambiq_apollo3_blue.dtsi b/dts/arm/ambiq/ambiq_apollo3_blue.dtsi index 5ae40c06790a2..aeff6c5d17a39 100644 --- a/dts/arm/ambiq/ambiq_apollo3_blue.dtsi +++ b/dts/arm/ambiq/ambiq_apollo3_blue.dtsi @@ -159,6 +159,21 @@ ambiq,pwrcfg = <&pwrcfg 0x8 0x800>; }; + bleif: bleif@5000c000 { + compatible = "ambiq,spi-bleif"; + reg = <0x5000c000 0x414>; + interrupts = <12 1>; + #address-cells = <1>; + #size-cells = <0>; + status = "disabled"; + ambiq,pwrcfg = <&pwrcfg 0x8 0x8000>; + + bt-hci@0 { + compatible = "ambiq,bt-hci-spi"; + reg = <0>; + }; + }; + pinctrl: pin-controller@40010000 { compatible = "ambiq,apollo3-pinctrl"; reg = <0x40010000 0x800>; diff --git a/dts/arm/ambiq/ambiq_apollo3p_blue.dtsi b/dts/arm/ambiq/ambiq_apollo3p_blue.dtsi index ac53b55883e2d..46199d52e9871 100644 --- a/dts/arm/ambiq/ambiq_apollo3p_blue.dtsi +++ b/dts/arm/ambiq/ambiq_apollo3p_blue.dtsi @@ -179,6 +179,21 @@ ambiq,pwrcfg = <&pwrcfg 0x8 0x2000>; }; + bleif: bleif@5000c000 { + compatible = "ambiq,spi-bleif"; + reg = <0x5000c000 0x414>; + interrupts = <12 1>; + #address-cells = <1>; + #size-cells = <0>; + status = "disabled"; + ambiq,pwrcfg = <&pwrcfg 0x8 0x8000>; + + bt-hci@0 { + compatible = "ambiq,bt-hci-spi"; + reg = <0>; + }; + }; + pinctrl: pin-controller@40010000 { compatible = "ambiq,apollo3-pinctrl"; reg = <0x40010000 0x800>; diff --git a/dts/bindings/spi/ambiq,spi-bleif.yaml b/dts/bindings/spi/ambiq,spi-bleif.yaml new file mode 100644 index 0000000000000..2be2ee1b9f8a2 --- /dev/null +++ b/dts/bindings/spi/ambiq,spi-bleif.yaml @@ -0,0 +1,18 @@ +# Copyright (c) 2024 Ambiq Micro Inc. +# SPDX-License-Identifier: Apache-2.0 + +description: | + This binding gives a representation of SPI controller in some Ambiq + Apollox Blue SOC (e.g. Apollo3 Blue) which uses BLEIF module for SPI + transceiver. + +compatible: "ambiq,spi-bleif" + +include: [spi-controller.yaml, pinctrl-device.yaml, ambiq-pwrcfg.yaml] + +properties: + reg: + required: true + + ambiq,pwrcfg: + required: true diff --git a/modules/hal_ambiq/Kconfig b/modules/hal_ambiq/Kconfig index b329d117c8979..10d3f785ce647 100644 --- a/modules/hal_ambiq/Kconfig +++ b/modules/hal_ambiq/Kconfig @@ -50,4 +50,9 @@ config AMBIQ_HAL_USE_HWINFO help Use the HWINFO driver from Ambiq HAL +config AMBIQ_HAL_USE_BLEIF + bool + help + Use the BLEIF driver from Ambiq HAL + endif # AMBIQ_HAL diff --git a/soc/ambiq/apollo3x/Kconfig.defconfig.apollo3_blue b/soc/ambiq/apollo3x/Kconfig.defconfig.apollo3_blue index c6c07932856c4..370ec60873453 100644 --- a/soc/ambiq/apollo3x/Kconfig.defconfig.apollo3_blue +++ b/soc/ambiq/apollo3x/Kconfig.defconfig.apollo3_blue @@ -7,4 +7,38 @@ if SOC_APOLLO3_BLUE config NUM_IRQS default 31 +config MAIN_STACK_SIZE + default 2048 if BT + +if BT + +choice BT_HCI_BUS_TYPE + default BT_AMBIQ_HCI +endchoice + +config BT_BUF_ACL_TX_COUNT + default 4 + +config BT_BUF_CMD_TX_SIZE + default 255 + +config BT_BUF_EVT_RX_SIZE + default 255 + +config BT_BUF_ACL_TX_SIZE + default 251 + +config BT_BUF_ACL_RX_SIZE + default 251 + +# L2CAP SDU/PDU TX MTU +# BT_L2CAP_RX_MTU = CONFIG_BT_BUF_ACL_RX_SIZE - BT_L2CAP_HDR_SIZE +config BT_L2CAP_TX_MTU + default 247 + +config BT_HCI_ACL_FLOW_CONTROL + default n + +endif # BT + endif # SOC_APOLLO3_BLUE diff --git a/soc/ambiq/apollo3x/Kconfig.defconfig.apollo3p_blue b/soc/ambiq/apollo3x/Kconfig.defconfig.apollo3p_blue index 8484dfad34752..930c8bc15f5da 100644 --- a/soc/ambiq/apollo3x/Kconfig.defconfig.apollo3p_blue +++ b/soc/ambiq/apollo3x/Kconfig.defconfig.apollo3p_blue @@ -7,4 +7,38 @@ if SOC_APOLLO3P_BLUE config NUM_IRQS default 33 +config MAIN_STACK_SIZE + default 2048 if BT + +if BT + +choice BT_HCI_BUS_TYPE + default BT_AMBIQ_HCI +endchoice + +config BT_BUF_ACL_TX_COUNT + default 4 + +config BT_BUF_CMD_TX_SIZE + default 255 + +config BT_BUF_EVT_RX_SIZE + default 255 + +config BT_BUF_ACL_TX_SIZE + default 251 + +config BT_BUF_ACL_RX_SIZE + default 251 + +# L2CAP SDU/PDU TX MTU +# BT_L2CAP_RX_MTU = CONFIG_BT_BUF_ACL_RX_SIZE - BT_L2CAP_HDR_SIZE +config BT_L2CAP_TX_MTU + default 247 + +config BT_HCI_ACL_FLOW_CONTROL + default n + +endif # BT + endif # SOC_APOLLO3P_BLUE diff --git a/west.yml b/west.yml index 4fd16a2f7d6f0..06376684fa279 100644 --- a/west.yml +++ b/west.yml @@ -142,7 +142,7 @@ manifest: groups: - hal - name: hal_ambiq - revision: 94dd874cd726ba8185a301e78337c5c39685123f + revision: fcbbd99e20db1432196f4aec92678bd1f5b19c96 path: modules/hal/ambiq groups: - hal