Merge pull request #2865 from embassy-rs/pico-bluetooth

Cyw43 / Pico W bluetooth, take 2
This commit is contained in:
Dario Nieuwenhuis 2024-08-05 19:19:12 +00:00 committed by GitHub
commit 46aa206a7c
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
21 changed files with 1037 additions and 84 deletions

2
ci.sh
View File

@ -173,6 +173,8 @@ cargo batch \
--- build --release --manifest-path cyw43/Cargo.toml --target thumbv6m-none-eabi --features 'defmt' \
--- build --release --manifest-path cyw43/Cargo.toml --target thumbv6m-none-eabi --features 'log,firmware-logs' \
--- build --release --manifest-path cyw43/Cargo.toml --target thumbv6m-none-eabi --features 'defmt,firmware-logs' \
--- build --release --manifest-path cyw43/Cargo.toml --target thumbv6m-none-eabi --features 'log,firmware-logs,bluetooth' \
--- build --release --manifest-path cyw43/Cargo.toml --target thumbv6m-none-eabi --features 'defmt,firmware-logs,bluetooth' \
--- build --release --manifest-path cyw43-pio/Cargo.toml --target thumbv6m-none-eabi --features '' \
--- build --release --manifest-path cyw43-pio/Cargo.toml --target thumbv6m-none-eabi --features 'overclock' \
--- build --release --manifest-path embassy-boot-nrf/Cargo.toml --target thumbv7em-none-eabi --features embassy-nrf/nrf52840 \

BIN
cyw43-firmware/43439A0.bin Executable file → Normal file

Binary file not shown.

Binary file not shown.

BIN
cyw43-firmware/43439A0_clm.bin Executable file → Normal file

Binary file not shown.

View File

@ -1,9 +1,14 @@
# WiFi firmware
# WiFi + Bluetooth firmware blobs
Firmware obtained from https://github.com/Infineon/wifi-host-driver/tree/master/WiFi_Host_Driver/resources/firmware/COMPONENT_43439
Firmware obtained from https://github.com/georgerobotics/cyw43-driver/tree/main/firmware
Licensed under the [Infineon Permissive Binary License](./LICENSE-permissive-binary-license-1.0.txt)
## Changelog
* 2023-07-28: synced with `ad3bad0` - Update 43439 fw from 7.95.55 ot 7.95.62
* 2023-08-21: synced with `a1dc885` - Update 43439 fw + clm to come from `wb43439A0_7_95_49_00_combined.h` + add Bluetooth firmware
* 2023-07-28: synced with `ad3bad0` - Update 43439 fw from 7.95.55 to 7.95.62
## Notes
If you update these files, please update the lengths in the `tests/rp/src/bin/cyw43_perf.rs` test (which relies on these files running from RAM).

View File

@ -181,7 +181,10 @@ where
let read_bits = read.len() * 32 + 32 - 1;
#[cfg(feature = "defmt")]
defmt::trace!("write={} read={}", write_bits, read_bits);
defmt::trace!("cmd_read write={} read={}", write_bits, read_bits);
#[cfg(feature = "defmt")]
defmt::trace!("cmd_read cmd = {:02x} len = {}", cmd, read.len());
unsafe {
instr::set_y(&mut self.sm, read_bits as u32);
@ -201,6 +204,10 @@ where
.rx()
.dma_pull(self.dma.reborrow(), slice::from_mut(&mut status))
.await;
#[cfg(feature = "defmt")]
defmt::trace!("cmd_read cmd = {:02x} len = {} read = {:08x}", cmd, read.len(), read);
status
}
}

View File

@ -10,8 +10,9 @@ repository = "https://github.com/embassy-rs/embassy"
documentation = "https://docs.embassy.dev/cyw43"
[features]
defmt = ["dep:defmt", "heapless/defmt-03", "embassy-time/defmt"]
defmt = ["dep:defmt", "heapless/defmt-03", "embassy-time/defmt", "bt-hci?/defmt", "embedded-io-async?/defmt-03"]
log = ["dep:log"]
bluetooth = ["dep:bt-hci", "dep:embedded-io-async"]
# Fetch console logs from the WiFi firmware and forward them to `log` or `defmt`.
firmware-logs = []
@ -31,9 +32,12 @@ futures = { version = "0.3.17", default-features = false, features = ["async-awa
embedded-hal-1 = { package = "embedded-hal", version = "1.0" }
num_enum = { version = "0.5.7", default-features = false }
heapless = "0.8.0"
# Bluetooth deps
embedded-io-async = { version = "0.6.0", optional = true }
bt-hci = { git = "https://github.com/alexmoon/bt-hci.git", rev = "b9cd5954f6bd89b535cad9c418e9fdf12812d7c3", optional = true, default-features = false }
[package.metadata.embassy_docs]
src_base = "https://github.com/embassy-rs/embassy/blob/cyw43-v$VERSION/cyw43/src/"
src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/cyw43/src/"

508
cyw43/src/bluetooth.rs Normal file
View File

@ -0,0 +1,508 @@
use core::cell::RefCell;
use core::future::Future;
use core::mem::MaybeUninit;
use bt_hci::transport::WithIndicator;
use bt_hci::{ControllerToHostPacket, FromHciBytes, HostToControllerPacket, PacketKind, WriteHci};
use embassy_futures::yield_now;
use embassy_sync::blocking_mutex::raw::NoopRawMutex;
use embassy_sync::zerocopy_channel;
use embassy_time::{Duration, Timer};
use embedded_hal_1::digital::OutputPin;
use crate::bus::Bus;
pub use crate::bus::SpiBusCyw43;
use crate::consts::*;
use crate::util::round_up;
use crate::{util, CHIP};
pub(crate) struct BtState {
rx: [BtPacketBuf; 4],
tx: [BtPacketBuf; 4],
inner: MaybeUninit<BtStateInnre<'static>>,
}
impl BtState {
pub const fn new() -> Self {
Self {
rx: [const { BtPacketBuf::new() }; 4],
tx: [const { BtPacketBuf::new() }; 4],
inner: MaybeUninit::uninit(),
}
}
}
struct BtStateInnre<'d> {
rx: zerocopy_channel::Channel<'d, NoopRawMutex, BtPacketBuf>,
tx: zerocopy_channel::Channel<'d, NoopRawMutex, BtPacketBuf>,
}
/// Bluetooth driver.
pub struct BtDriver<'d> {
rx: RefCell<zerocopy_channel::Receiver<'d, NoopRawMutex, BtPacketBuf>>,
tx: RefCell<zerocopy_channel::Sender<'d, NoopRawMutex, BtPacketBuf>>,
}
pub(crate) struct BtRunner<'d> {
pub(crate) tx_chan: zerocopy_channel::Receiver<'d, NoopRawMutex, BtPacketBuf>,
rx_chan: zerocopy_channel::Sender<'d, NoopRawMutex, BtPacketBuf>,
// Bluetooth circular buffers
addr: u32,
h2b_write_pointer: u32,
b2h_read_pointer: u32,
}
const BT_HCI_MTU: usize = 1024;
/// Represents a packet of size MTU.
pub(crate) struct BtPacketBuf {
pub(crate) len: usize,
pub(crate) buf: [u8; BT_HCI_MTU],
}
impl BtPacketBuf {
/// Create a new packet buffer.
pub const fn new() -> Self {
Self {
len: 0,
buf: [0; BT_HCI_MTU],
}
}
}
pub(crate) fn new<'d>(state: &'d mut BtState) -> (BtRunner<'d>, BtDriver<'d>) {
// safety: this is a self-referential struct, however:
// - it can't move while the `'d` borrow is active.
// - when the borrow ends, the dangling references inside the MaybeUninit will never be used again.
let state_uninit: *mut MaybeUninit<BtStateInnre<'d>> =
(&mut state.inner as *mut MaybeUninit<BtStateInnre<'static>>).cast();
let state = unsafe { &mut *state_uninit }.write(BtStateInnre {
rx: zerocopy_channel::Channel::new(&mut state.rx[..]),
tx: zerocopy_channel::Channel::new(&mut state.tx[..]),
});
let (rx_sender, rx_receiver) = state.rx.split();
let (tx_sender, tx_receiver) = state.tx.split();
(
BtRunner {
tx_chan: tx_receiver,
rx_chan: rx_sender,
addr: 0,
h2b_write_pointer: 0,
b2h_read_pointer: 0,
},
BtDriver {
rx: RefCell::new(rx_receiver),
tx: RefCell::new(tx_sender),
},
)
}
pub(crate) struct CybtFwCb<'a> {
pub p_next_line_start: &'a [u8],
}
pub(crate) struct HexFileData<'a> {
pub addr_mode: i32,
pub hi_addr: u16,
pub dest_addr: u32,
pub p_ds: &'a mut [u8],
}
pub(crate) fn read_firmware_patch_line(p_btfw_cb: &mut CybtFwCb, hfd: &mut HexFileData) -> u32 {
let mut abs_base_addr32 = 0;
loop {
let num_bytes = p_btfw_cb.p_next_line_start[0];
p_btfw_cb.p_next_line_start = &p_btfw_cb.p_next_line_start[1..];
let addr = (p_btfw_cb.p_next_line_start[0] as u16) << 8 | p_btfw_cb.p_next_line_start[1] as u16;
p_btfw_cb.p_next_line_start = &p_btfw_cb.p_next_line_start[2..];
let line_type = p_btfw_cb.p_next_line_start[0];
p_btfw_cb.p_next_line_start = &p_btfw_cb.p_next_line_start[1..];
if num_bytes == 0 {
break;
}
hfd.p_ds[..num_bytes as usize].copy_from_slice(&p_btfw_cb.p_next_line_start[..num_bytes as usize]);
p_btfw_cb.p_next_line_start = &p_btfw_cb.p_next_line_start[num_bytes as usize..];
match line_type {
BTFW_HEX_LINE_TYPE_EXTENDED_ADDRESS => {
hfd.hi_addr = (hfd.p_ds[0] as u16) << 8 | hfd.p_ds[1] as u16;
hfd.addr_mode = BTFW_ADDR_MODE_EXTENDED;
}
BTFW_HEX_LINE_TYPE_EXTENDED_SEGMENT_ADDRESS => {
hfd.hi_addr = (hfd.p_ds[0] as u16) << 8 | hfd.p_ds[1] as u16;
hfd.addr_mode = BTFW_ADDR_MODE_SEGMENT;
}
BTFW_HEX_LINE_TYPE_ABSOLUTE_32BIT_ADDRESS => {
abs_base_addr32 = (hfd.p_ds[0] as u32) << 24
| (hfd.p_ds[1] as u32) << 16
| (hfd.p_ds[2] as u32) << 8
| hfd.p_ds[3] as u32;
hfd.addr_mode = BTFW_ADDR_MODE_LINEAR32;
}
BTFW_HEX_LINE_TYPE_DATA => {
hfd.dest_addr = addr as u32;
match hfd.addr_mode {
BTFW_ADDR_MODE_EXTENDED => hfd.dest_addr += (hfd.hi_addr as u32) << 16,
BTFW_ADDR_MODE_SEGMENT => hfd.dest_addr += (hfd.hi_addr as u32) << 4,
BTFW_ADDR_MODE_LINEAR32 => hfd.dest_addr += abs_base_addr32,
_ => {}
}
return num_bytes as u32;
}
_ => {}
}
}
0
}
impl<'a> BtRunner<'a> {
pub(crate) async fn init_bluetooth(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>, firmware: &[u8]) {
trace!("init_bluetooth");
bus.bp_write32(CHIP.bluetooth_base_address + BT2WLAN_PWRUP_ADDR, BT2WLAN_PWRUP_WAKE)
.await;
Timer::after(Duration::from_millis(2)).await;
self.upload_bluetooth_firmware(bus, firmware).await;
self.wait_bt_ready(bus).await;
self.init_bt_buffers(bus).await;
self.wait_bt_awake(bus).await;
self.bt_set_host_ready(bus).await;
self.bt_toggle_intr(bus).await;
}
pub(crate) async fn upload_bluetooth_firmware(
&mut self,
bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>,
firmware: &[u8],
) {
// read version
let version_length = firmware[0];
let _version = &firmware[1..=version_length as usize];
// skip version + 1 extra byte as per cybt_shared_bus_driver.c
let firmware = &firmware[version_length as usize + 2..];
// buffers
let mut data_buffer: [u8; 0x100] = [0; 0x100];
let mut aligned_data_buffer: [u8; 0x100] = [0; 0x100];
// structs
let mut btfw_cb = CybtFwCb {
p_next_line_start: firmware,
};
let mut hfd = HexFileData {
addr_mode: BTFW_ADDR_MODE_EXTENDED,
hi_addr: 0,
dest_addr: 0,
p_ds: &mut data_buffer,
};
loop {
let num_fw_bytes = read_firmware_patch_line(&mut btfw_cb, &mut hfd);
if num_fw_bytes == 0 {
break;
}
let fw_bytes = &hfd.p_ds[0..num_fw_bytes as usize];
let mut dest_start_addr = hfd.dest_addr + CHIP.bluetooth_base_address;
let mut aligned_data_buffer_index: usize = 0;
// pad start
if !util::is_aligned(dest_start_addr, 4) {
let num_pad_bytes = dest_start_addr % 4;
let padded_dest_start_addr = util::round_down(dest_start_addr, 4);
let memory_value = bus.bp_read32(padded_dest_start_addr).await;
let memory_value_bytes = memory_value.to_le_bytes();
// Copy the previous memory value's bytes to the start
for i in 0..num_pad_bytes as usize {
aligned_data_buffer[aligned_data_buffer_index] = memory_value_bytes[i];
aligned_data_buffer_index += 1;
}
// Copy the firmware bytes after the padding bytes
for i in 0..num_fw_bytes as usize {
aligned_data_buffer[aligned_data_buffer_index] = fw_bytes[i];
aligned_data_buffer_index += 1;
}
dest_start_addr = padded_dest_start_addr;
} else {
// Directly copy fw_bytes into aligned_data_buffer if no start padding is required
for i in 0..num_fw_bytes as usize {
aligned_data_buffer[aligned_data_buffer_index] = fw_bytes[i];
aligned_data_buffer_index += 1;
}
}
// pad end
let mut dest_end_addr = dest_start_addr + aligned_data_buffer_index as u32;
if !util::is_aligned(dest_end_addr, 4) {
let offset = dest_end_addr % 4;
let num_pad_bytes_end = 4 - offset;
let padded_dest_end_addr = util::round_down(dest_end_addr, 4);
let memory_value = bus.bp_read32(padded_dest_end_addr).await;
let memory_value_bytes = memory_value.to_le_bytes();
// Append the necessary memory bytes to pad the end of aligned_data_buffer
for i in offset..4 {
aligned_data_buffer[aligned_data_buffer_index] = memory_value_bytes[i as usize];
aligned_data_buffer_index += 1;
}
dest_end_addr += num_pad_bytes_end;
} else {
// pad end alignment not needed
}
let buffer_to_write = &aligned_data_buffer[0..aligned_data_buffer_index as usize];
assert!(dest_start_addr % 4 == 0);
assert!(dest_end_addr % 4 == 0);
assert!(aligned_data_buffer_index % 4 == 0);
bus.bp_write(dest_start_addr, buffer_to_write).await;
}
}
pub(crate) async fn wait_bt_ready(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>) {
trace!("wait_bt_ready");
let mut success = false;
for _ in 0..300 {
let val = bus.bp_read32(BT_CTRL_REG_ADDR).await;
trace!("BT_CTRL_REG_ADDR = {:08x}", val);
if val & BTSDIO_REG_FW_RDY_BITMASK != 0 {
success = true;
break;
}
Timer::after(Duration::from_millis(1)).await;
}
assert!(success == true);
}
pub(crate) async fn wait_bt_awake(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>) {
trace!("wait_bt_awake");
let mut success = false;
for _ in 0..300 {
let val = bus.bp_read32(BT_CTRL_REG_ADDR).await;
trace!("BT_CTRL_REG_ADDR = {:08x}", val);
if val & BTSDIO_REG_BT_AWAKE_BITMASK != 0 {
success = true;
break;
}
Timer::after(Duration::from_millis(1)).await;
}
assert!(success == true);
}
pub(crate) async fn bt_set_host_ready(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>) {
trace!("bt_set_host_ready");
let old_val = bus.bp_read32(HOST_CTRL_REG_ADDR).await;
// TODO: do we need to swap endianness on this read?
let new_val = old_val | BTSDIO_REG_SW_RDY_BITMASK;
bus.bp_write32(HOST_CTRL_REG_ADDR, new_val).await;
}
// TODO: use this
#[allow(dead_code)]
pub(crate) async fn bt_set_awake(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>, awake: bool) {
trace!("bt_set_awake");
let old_val = bus.bp_read32(HOST_CTRL_REG_ADDR).await;
// TODO: do we need to swap endianness on this read?
let new_val = if awake {
old_val | BTSDIO_REG_WAKE_BT_BITMASK
} else {
old_val & !BTSDIO_REG_WAKE_BT_BITMASK
};
bus.bp_write32(HOST_CTRL_REG_ADDR, new_val).await;
}
pub(crate) async fn bt_toggle_intr(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>) {
trace!("bt_toggle_intr");
let old_val = bus.bp_read32(HOST_CTRL_REG_ADDR).await;
// TODO: do we need to swap endianness on this read?
let new_val = old_val ^ BTSDIO_REG_DATA_VALID_BITMASK;
bus.bp_write32(HOST_CTRL_REG_ADDR, new_val).await;
}
// TODO: use this
#[allow(dead_code)]
pub(crate) async fn bt_set_intr(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>) {
trace!("bt_set_intr");
let old_val = bus.bp_read32(HOST_CTRL_REG_ADDR).await;
let new_val = old_val | BTSDIO_REG_DATA_VALID_BITMASK;
bus.bp_write32(HOST_CTRL_REG_ADDR, new_val).await;
}
pub(crate) async fn init_bt_buffers(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>) {
trace!("init_bt_buffers");
self.addr = bus.bp_read32(WLAN_RAM_BASE_REG_ADDR).await;
assert!(self.addr != 0);
trace!("wlan_ram_base_addr = {:08x}", self.addr);
bus.bp_write32(self.addr + BTSDIO_OFFSET_HOST2BT_IN, 0).await;
bus.bp_write32(self.addr + BTSDIO_OFFSET_HOST2BT_OUT, 0).await;
bus.bp_write32(self.addr + BTSDIO_OFFSET_BT2HOST_IN, 0).await;
bus.bp_write32(self.addr + BTSDIO_OFFSET_BT2HOST_OUT, 0).await;
}
async fn bt_bus_request(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>) {
// TODO: CYW43_THREAD_ENTER mutex?
self.bt_set_awake(bus, true).await;
self.wait_bt_awake(bus).await;
}
pub(crate) async fn hci_write(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>) {
self.bt_bus_request(bus).await;
// NOTE(unwrap): we only call this when we do have a packet in the queue.
let buf = self.tx_chan.try_receive().unwrap();
debug!("HCI tx: {:02x}", crate::fmt::Bytes(&buf.buf[..buf.len]));
let len = buf.len as u32 - 1; // len doesn't include hci type byte
let rounded_len = round_up(len, 4);
let total_len = 4 + rounded_len;
let read_pointer = bus.bp_read32(self.addr + BTSDIO_OFFSET_HOST2BT_OUT).await;
let available = read_pointer.wrapping_sub(self.h2b_write_pointer + 4) % BTSDIO_FWBUF_SIZE;
if available < total_len {
warn!(
"bluetooth tx queue full, retrying. len {} available {}",
total_len, available
);
yield_now().await;
return;
}
// Build header
let mut header = [0u8; 4];
header[0] = len as u8;
header[1] = (len >> 8) as u8;
header[2] = (len >> 16) as u8;
header[3] = buf.buf[0]; // HCI type byte
// Write header
let addr = self.addr + BTSDIO_OFFSET_HOST_WRITE_BUF + self.h2b_write_pointer;
bus.bp_write(addr, &header).await;
self.h2b_write_pointer = (self.h2b_write_pointer + 4) % BTSDIO_FWBUF_SIZE;
// Write payload.
let payload = &buf.buf[1..][..rounded_len as usize];
if self.h2b_write_pointer as usize + payload.len() > BTSDIO_FWBUF_SIZE as usize {
// wraparound
let n = BTSDIO_FWBUF_SIZE - self.h2b_write_pointer;
let addr = self.addr + BTSDIO_OFFSET_HOST_WRITE_BUF + self.h2b_write_pointer;
bus.bp_write(addr, &payload[..n as usize]).await;
let addr = self.addr + BTSDIO_OFFSET_HOST_WRITE_BUF;
bus.bp_write(addr, &payload[n as usize..]).await;
} else {
// no wraparound
let addr = self.addr + BTSDIO_OFFSET_HOST_WRITE_BUF + self.h2b_write_pointer;
bus.bp_write(addr, payload).await;
}
self.h2b_write_pointer = (self.h2b_write_pointer + payload.len() as u32) % BTSDIO_FWBUF_SIZE;
// Update pointer.
bus.bp_write32(self.addr + BTSDIO_OFFSET_HOST2BT_IN, self.h2b_write_pointer)
.await;
self.bt_toggle_intr(bus).await;
self.tx_chan.receive_done();
}
async fn bt_has_work(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>) -> bool {
let int_status = bus.bp_read32(CHIP.sdiod_core_base_address + SDIO_INT_STATUS).await;
if int_status & I_HMB_FC_CHANGE != 0 {
bus.bp_write32(
CHIP.sdiod_core_base_address + SDIO_INT_STATUS,
int_status & I_HMB_FC_CHANGE,
)
.await;
return true;
}
return false;
}
pub(crate) async fn handle_irq(&mut self, bus: &mut Bus<impl OutputPin, impl SpiBusCyw43>) {
if self.bt_has_work(bus).await {
loop {
// Check if we have data.
let write_pointer = bus.bp_read32(self.addr + BTSDIO_OFFSET_BT2HOST_IN).await;
let available = write_pointer.wrapping_sub(self.b2h_read_pointer) % BTSDIO_FWBUF_SIZE;
if available == 0 {
break;
}
// read header
let mut header = [0u8; 4];
let addr = self.addr + BTSDIO_OFFSET_HOST_READ_BUF + self.b2h_read_pointer;
bus.bp_read(addr, &mut header).await;
// calc length
let len = header[0] as u32 | ((header[1]) as u32) << 8 | ((header[2]) as u32) << 16;
let rounded_len = round_up(len, 4);
if available < 4 + rounded_len {
warn!("ringbuf data not enough for a full packet?");
break;
}
self.b2h_read_pointer = (self.b2h_read_pointer + 4) % BTSDIO_FWBUF_SIZE;
// Obtain a buf from the channel.
let buf = self.rx_chan.send().await;
buf.buf[0] = header[3]; // hci packet type
let payload = &mut buf.buf[1..][..rounded_len as usize];
if self.b2h_read_pointer as usize + payload.len() > BTSDIO_FWBUF_SIZE as usize {
// wraparound
let n = BTSDIO_FWBUF_SIZE - self.b2h_read_pointer;
let addr = self.addr + BTSDIO_OFFSET_HOST_READ_BUF + self.b2h_read_pointer;
bus.bp_read(addr, &mut payload[..n as usize]).await;
let addr = self.addr + BTSDIO_OFFSET_HOST_READ_BUF;
bus.bp_read(addr, &mut payload[n as usize..]).await;
} else {
// no wraparound
let addr = self.addr + BTSDIO_OFFSET_HOST_READ_BUF + self.b2h_read_pointer;
bus.bp_read(addr, payload).await;
}
self.b2h_read_pointer = (self.b2h_read_pointer + payload.len() as u32) % BTSDIO_FWBUF_SIZE;
bus.bp_write32(self.addr + BTSDIO_OFFSET_BT2HOST_OUT, self.b2h_read_pointer)
.await;
buf.len = 1 + len as usize;
debug!("HCI rx: {:02x}", crate::fmt::Bytes(&buf.buf[..buf.len]));
self.rx_chan.send_done();
self.bt_toggle_intr(bus).await;
}
}
}
}
impl<'d> embedded_io_async::ErrorType for BtDriver<'d> {
type Error = core::convert::Infallible;
}
impl<'d> bt_hci::transport::Transport for BtDriver<'d> {
fn read<'a>(&self, rx: &'a mut [u8]) -> impl Future<Output = Result<ControllerToHostPacket<'a>, Self::Error>> {
async {
let ch = &mut *self.rx.borrow_mut();
let buf = ch.receive().await;
let n = buf.len;
assert!(n < rx.len());
rx[..n].copy_from_slice(&buf.buf[..n]);
ch.receive_done();
let kind = PacketKind::from_hci_bytes_complete(&rx[..1]).unwrap();
let (res, _) = ControllerToHostPacket::from_hci_bytes_with_kind(kind, &rx[1..n]).unwrap();
Ok(res)
}
}
/// Write a complete HCI packet from the tx buffer
fn write<T: HostToControllerPacket>(&self, val: &T) -> impl Future<Output = Result<(), Self::Error>> {
async {
let ch = &mut *self.tx.borrow_mut();
let buf = ch.send().await;
let buf_len = buf.buf.len();
let mut slice = &mut buf.buf[..];
WithIndicator::new(val).write_hci(&mut slice).unwrap();
buf.len = buf_len - slice.len();
ch.send_done();
Ok(())
}
}
}

View File

@ -4,7 +4,7 @@ use embedded_hal_1::digital::OutputPin;
use futures::FutureExt;
use crate::consts::*;
use crate::slice8_mut;
use crate::util::slice8_mut;
/// Custom Spi Trait that _only_ supports the bus operation of the cyw43
/// Implementors are expected to hold the CS pin low during an operation.
@ -48,44 +48,91 @@ where
}
}
pub async fn init(&mut self) {
pub async fn init(&mut self, bluetooth_enabled: bool) {
// Reset
trace!("WL_REG off/on");
self.pwr.set_low().unwrap();
Timer::after_millis(20).await;
self.pwr.set_high().unwrap();
Timer::after_millis(250).await;
trace!("read REG_BUS_TEST_RO");
while self
.read32_swapped(REG_BUS_TEST_RO)
.read32_swapped(FUNC_BUS, REG_BUS_TEST_RO)
.inspect(|v| trace!("{:#x}", v))
.await
!= FEEDBEAD
{}
self.write32_swapped(REG_BUS_TEST_RW, TEST_PATTERN).await;
let val = self.read32_swapped(REG_BUS_TEST_RW).await;
trace!("write REG_BUS_TEST_RW");
self.write32_swapped(FUNC_BUS, REG_BUS_TEST_RW, TEST_PATTERN).await;
let val = self.read32_swapped(FUNC_BUS, REG_BUS_TEST_RW).await;
trace!("{:#x}", val);
assert_eq!(val, TEST_PATTERN);
let val = self.read32_swapped(REG_BUS_CTRL).await;
trace!("read REG_BUS_CTRL");
let val = self.read32_swapped(FUNC_BUS, REG_BUS_CTRL).await;
trace!("{:#010b}", (val & 0xff));
// 32-bit word length, little endian (which is the default endianess).
// TODO: C library is uint32_t val = WORD_LENGTH_32 | HIGH_SPEED_MODE| ENDIAN_BIG | INTERRUPT_POLARITY_HIGH | WAKE_UP | 0x4 << (8 * SPI_RESPONSE_DELAY) | INTR_WITH_STATUS << (8 * SPI_STATUS_ENABLE);
trace!("write REG_BUS_CTRL");
self.write32_swapped(
FUNC_BUS,
REG_BUS_CTRL,
WORD_LENGTH_32 | HIGH_SPEED | INTERRUPT_HIGH | WAKE_UP | STATUS_ENABLE | INTERRUPT_WITH_STATUS,
WORD_LENGTH_32
| HIGH_SPEED
| INTERRUPT_POLARITY_HIGH
| WAKE_UP
| 0x4 << (8 * REG_BUS_RESPONSE_DELAY)
| STATUS_ENABLE << (8 * REG_BUS_STATUS_ENABLE)
| INTR_WITH_STATUS << (8 * REG_BUS_STATUS_ENABLE),
)
.await;
trace!("read REG_BUS_CTRL");
let val = self.read8(FUNC_BUS, REG_BUS_CTRL).await;
trace!("{:#b}", val);
// TODO: C doesn't do this? i doubt it messes anything up
trace!("read REG_BUS_TEST_RO");
let val = self.read32(FUNC_BUS, REG_BUS_TEST_RO).await;
trace!("{:#x}", val);
assert_eq!(val, FEEDBEAD);
// TODO: C doesn't do this? i doubt it messes anything up
trace!("read REG_BUS_TEST_RW");
let val = self.read32(FUNC_BUS, REG_BUS_TEST_RW).await;
trace!("{:#x}", val);
assert_eq!(val, TEST_PATTERN);
trace!("write SPI_RESP_DELAY_F1 CYW43_BACKPLANE_READ_PAD_LEN_BYTES");
self.write8(FUNC_BUS, SPI_RESP_DELAY_F1, WHD_BUS_SPI_BACKPLANE_READ_PADD_SIZE)
.await;
// TODO: Make sure error interrupt bits are clear?
// cyw43_write_reg_u8(self, BUS_FUNCTION, SPI_INTERRUPT_REGISTER, DATA_UNAVAILABLE | COMMAND_ERROR | DATA_ERROR | F1_OVERFLOW) != 0)
trace!("Make sure error interrupt bits are clear");
self.write8(
FUNC_BUS,
REG_BUS_INTERRUPT,
(IRQ_DATA_UNAVAILABLE | IRQ_COMMAND_ERROR | IRQ_DATA_ERROR | IRQ_F1_OVERFLOW) as u8,
)
.await;
// Enable a selection of interrupts
// TODO: why not all of these F2_F3_FIFO_RD_UNDERFLOW | F2_F3_FIFO_WR_OVERFLOW | COMMAND_ERROR | DATA_ERROR | F2_PACKET_AVAILABLE | F1_OVERFLOW | F1_INTR
trace!("enable a selection of interrupts");
let mut val = IRQ_F2_F3_FIFO_RD_UNDERFLOW
| IRQ_F2_F3_FIFO_WR_OVERFLOW
| IRQ_COMMAND_ERROR
| IRQ_DATA_ERROR
| IRQ_F2_PACKET_AVAILABLE
| IRQ_F1_OVERFLOW;
if bluetooth_enabled {
val = val | IRQ_F1_INTR;
}
self.write16(FUNC_BUS, REG_BUS_INTERRUPT_ENABLE, val).await;
}
pub async fn wlan_read(&mut self, buf: &mut [u32], len_in_u8: u32) {
@ -107,6 +154,8 @@ where
#[allow(unused)]
pub async fn bp_read(&mut self, mut addr: u32, mut data: &mut [u8]) {
trace!("bp_read addr = {:08x}", addr);
// It seems the HW force-aligns the addr
// to 2 if data.len() >= 2
// to 4 if data.len() >= 4
@ -140,6 +189,8 @@ where
}
pub async fn bp_write(&mut self, mut addr: u32, mut data: &[u8]) {
trace!("bp_write addr = {:08x}", addr);
// It seems the HW force-aligns the addr
// to 2 if data.len() >= 2
// to 4 if data.len() >= 4
@ -196,23 +247,32 @@ where
}
async fn backplane_readn(&mut self, addr: u32, len: u32) -> u32 {
trace!("backplane_readn addr = {:08x} len = {}", addr, len);
self.backplane_set_window(addr).await;
let mut bus_addr = addr & BACKPLANE_ADDRESS_MASK;
if len == 4 {
bus_addr |= BACKPLANE_ADDRESS_32BIT_FLAG
bus_addr |= BACKPLANE_ADDRESS_32BIT_FLAG;
}
self.readn(FUNC_BACKPLANE, bus_addr, len).await
let val = self.readn(FUNC_BACKPLANE, bus_addr, len).await;
trace!("backplane_readn addr = {:08x} len = {} val = {:08x}", addr, len, val);
return val;
}
async fn backplane_writen(&mut self, addr: u32, val: u32, len: u32) {
trace!("backplane_writen addr = {:08x} len = {} val = {:08x}", addr, len, val);
self.backplane_set_window(addr).await;
let mut bus_addr = addr & BACKPLANE_ADDRESS_MASK;
if len == 4 {
bus_addr |= BACKPLANE_ADDRESS_32BIT_FLAG
bus_addr |= BACKPLANE_ADDRESS_32BIT_FLAG;
}
self.writen(FUNC_BACKPLANE, bus_addr, val, len).await
self.writen(FUNC_BACKPLANE, bus_addr, val, len).await;
}
async fn backplane_set_window(&mut self, addr: u32) {
@ -293,8 +353,8 @@ where
self.status = self.spi.cmd_write(&[cmd, val]).await;
}
async fn read32_swapped(&mut self, addr: u32) -> u32 {
let cmd = cmd_word(READ, INC_ADDR, FUNC_BUS, addr, 4);
async fn read32_swapped(&mut self, func: u32, addr: u32) -> u32 {
let cmd = cmd_word(READ, INC_ADDR, func, addr, 4);
let cmd = swap16(cmd);
let mut buf = [0; 1];
@ -303,8 +363,8 @@ where
swap16(buf[0])
}
async fn write32_swapped(&mut self, addr: u32, val: u32) {
let cmd = cmd_word(WRITE, INC_ADDR, FUNC_BUS, addr, 4);
async fn write32_swapped(&mut self, func: u32, addr: u32, val: u32) {
let cmd = cmd_word(WRITE, INC_ADDR, func, addr, 4);
let buf = [swap16(cmd), swap16(val)];
self.status = self.spi.cmd_write(&buf).await;

View File

@ -5,19 +5,33 @@ pub(crate) const FUNC_BACKPLANE: u32 = 1;
pub(crate) const FUNC_WLAN: u32 = 2;
pub(crate) const FUNC_BT: u32 = 3;
// Register addresses
pub(crate) const REG_BUS_CTRL: u32 = 0x0;
pub(crate) const REG_BUS_RESPONSE_DELAY: u32 = 0x1;
pub(crate) const REG_BUS_STATUS_ENABLE: u32 = 0x2;
pub(crate) const REG_BUS_INTERRUPT: u32 = 0x04; // 16 bits - Interrupt status
pub(crate) const REG_BUS_INTERRUPT_ENABLE: u32 = 0x06; // 16 bits - Interrupt mask
pub(crate) const REG_BUS_STATUS: u32 = 0x8;
pub(crate) const REG_BUS_TEST_RO: u32 = 0x14;
pub(crate) const REG_BUS_TEST_RW: u32 = 0x18;
pub(crate) const REG_BUS_RESP_DELAY: u32 = 0x1c;
// SPI_BUS_CONTROL Bits
pub(crate) const WORD_LENGTH_32: u32 = 0x1;
pub(crate) const ENDIAN_BIG: u32 = 0x2;
pub(crate) const CLOCK_PHASE: u32 = 0x4;
pub(crate) const CLOCK_POLARITY: u32 = 0x8;
pub(crate) const HIGH_SPEED: u32 = 0x10;
pub(crate) const INTERRUPT_HIGH: u32 = 1 << 5;
pub(crate) const WAKE_UP: u32 = 1 << 7;
pub(crate) const STATUS_ENABLE: u32 = 1 << 16;
pub(crate) const INTERRUPT_WITH_STATUS: u32 = 1 << 17;
pub(crate) const INTERRUPT_POLARITY_HIGH: u32 = 0x20;
pub(crate) const WAKE_UP: u32 = 0x80;
// SPI_STATUS_ENABLE bits
pub(crate) const STATUS_ENABLE: u32 = 0x01;
pub(crate) const INTR_WITH_STATUS: u32 = 0x02;
pub(crate) const RESP_DELAY_ALL: u32 = 0x04;
pub(crate) const DWORD_PKT_LEN_EN: u32 = 0x08;
pub(crate) const CMD_ERR_CHK_EN: u32 = 0x20;
pub(crate) const DATA_ERR_CHK_EN: u32 = 0x40;
// SPI_STATUS_REGISTER bits
pub(crate) const STATUS_DATA_NOT_AVAILABLE: u32 = 0x00000001;
@ -51,6 +65,13 @@ pub(crate) const REG_BACKPLANE_READ_FRAME_BC_HIGH: u32 = 0x1001C;
pub(crate) const REG_BACKPLANE_WAKEUP_CTRL: u32 = 0x1001E;
pub(crate) const REG_BACKPLANE_SLEEP_CSR: u32 = 0x1001F;
pub(crate) const I_HMB_SW_MASK: u32 = 0x000000f0;
pub(crate) const I_HMB_FC_CHANGE: u32 = 1 << 5;
pub(crate) const SDIO_INT_STATUS: u32 = 0x20;
pub(crate) const SDIO_INT_HOST_MASK: u32 = 0x24;
pub(crate) const SPI_F2_WATERMARK: u8 = 0x20;
pub(crate) const BACKPLANE_WINDOW_SIZE: usize = 0x8000;
pub(crate) const BACKPLANE_ADDRESS_MASK: u32 = 0x7FFF;
pub(crate) const BACKPLANE_ADDRESS_32BIT_FLAG: u32 = 0x08000;
@ -119,6 +140,44 @@ pub(crate) const WPA2_SECURITY: u32 = 0x00400000;
pub(crate) const MIN_PSK_LEN: usize = 8;
pub(crate) const MAX_PSK_LEN: usize = 64;
// Bluetooth firmware extraction constants.
pub(crate) const BTFW_ADDR_MODE_UNKNOWN: i32 = 0;
pub(crate) const BTFW_ADDR_MODE_EXTENDED: i32 = 1;
pub(crate) const BTFW_ADDR_MODE_SEGMENT: i32 = 2;
pub(crate) const BTFW_ADDR_MODE_LINEAR32: i32 = 3;
pub(crate) const BTFW_HEX_LINE_TYPE_DATA: u8 = 0;
pub(crate) const BTFW_HEX_LINE_TYPE_END_OF_DATA: u8 = 1;
pub(crate) const BTFW_HEX_LINE_TYPE_EXTENDED_SEGMENT_ADDRESS: u8 = 2;
pub(crate) const BTFW_HEX_LINE_TYPE_EXTENDED_ADDRESS: u8 = 4;
pub(crate) const BTFW_HEX_LINE_TYPE_ABSOLUTE_32BIT_ADDRESS: u8 = 5;
// Bluetooth constants.
pub(crate) const SPI_RESP_DELAY_F1: u32 = 0x001d;
pub(crate) const WHD_BUS_SPI_BACKPLANE_READ_PADD_SIZE: u8 = 4;
pub(crate) const BT2WLAN_PWRUP_WAKE: u32 = 3;
pub(crate) const BT2WLAN_PWRUP_ADDR: u32 = 0x640894;
pub(crate) const BT_CTRL_REG_ADDR: u32 = 0x18000c7c;
pub(crate) const HOST_CTRL_REG_ADDR: u32 = 0x18000d6c;
pub(crate) const WLAN_RAM_BASE_REG_ADDR: u32 = 0x18000d68;
pub(crate) const BTSDIO_REG_DATA_VALID_BITMASK: u32 = 1 << 1;
pub(crate) const BTSDIO_REG_BT_AWAKE_BITMASK: u32 = 1 << 8;
pub(crate) const BTSDIO_REG_WAKE_BT_BITMASK: u32 = 1 << 17;
pub(crate) const BTSDIO_REG_SW_RDY_BITMASK: u32 = 1 << 24;
pub(crate) const BTSDIO_REG_FW_RDY_BITMASK: u32 = 1 << 24;
pub(crate) const BTSDIO_FWBUF_SIZE: u32 = 0x1000;
pub(crate) const BTSDIO_OFFSET_HOST_WRITE_BUF: u32 = 0;
pub(crate) const BTSDIO_OFFSET_HOST_READ_BUF: u32 = BTSDIO_FWBUF_SIZE;
pub(crate) const BTSDIO_OFFSET_HOST2BT_IN: u32 = 0x00002000;
pub(crate) const BTSDIO_OFFSET_HOST2BT_OUT: u32 = 0x00002004;
pub(crate) const BTSDIO_OFFSET_BT2HOST_IN: u32 = 0x00002008;
pub(crate) const BTSDIO_OFFSET_BT2HOST_OUT: u32 = 0x0000200C;
// Security type (authentication and encryption types are combined using bit mask)
#[allow(non_camel_case_types)]
#[derive(Copy, Clone, PartialEq)]

View File

@ -83,8 +83,7 @@ impl<'a> Control<'a> {
}
}
/// Initialize WiFi controller.
pub async fn init(&mut self, clm: &[u8]) {
async fn load_clm(&mut self, clm: &[u8]) {
const CHUNK_SIZE: usize = 1024;
debug!("Downloading CLM...");
@ -116,6 +115,11 @@ impl<'a> Control<'a> {
// check clmload ok
assert_eq!(self.get_iovar_u32("clmload_status").await, 0);
}
/// Initialize WiFi controller.
pub async fn init(&mut self, clm: &[u8]) {
self.load_clm(&clm).await;
debug!("Configuring misc stuff...");
@ -186,7 +190,7 @@ impl<'a> Control<'a> {
self.state_ch.set_hardware_address(HardwareAddress::Ethernet(mac_addr));
debug!("INIT DONE");
debug!("cyw43 control init done");
}
/// Set the WiFi interface up.

View File

@ -8,18 +8,18 @@
// This mod MUST go first, so that the others see its macros.
pub(crate) mod fmt;
#[cfg(feature = "bluetooth")]
mod bluetooth;
mod bus;
mod consts;
mod control;
mod countries;
mod events;
mod ioctl;
mod structs;
mod control;
mod nvram;
mod runner;
use core::slice;
mod structs;
mod util;
use embassy_net_driver_channel as ch;
use embedded_hal_1::digital::OutputPin;
@ -56,6 +56,7 @@ impl Core {
struct Chip {
arm_core_base_address: u32,
socsram_base_address: u32,
bluetooth_base_address: u32,
socsram_wrapper_base_address: u32,
sdiod_core_base_address: u32,
pmu_base_address: u32,
@ -83,6 +84,7 @@ const WRAPPER_REGISTER_OFFSET: u32 = 0x100000;
const CHIP: Chip = Chip {
arm_core_base_address: 0x18003000 + WRAPPER_REGISTER_OFFSET,
socsram_base_address: 0x18004000,
bluetooth_base_address: 0x19000000,
socsram_wrapper_base_address: 0x18004000 + WRAPPER_REGISTER_OFFSET,
sdiod_core_base_address: 0x18002000,
pmu_base_address: 0x18000000,
@ -107,6 +109,12 @@ const CHIP: Chip = Chip {
/// Driver state.
pub struct State {
ioctl_state: IoctlState,
net: NetState,
#[cfg(feature = "bluetooth")]
bt: bluetooth::BtState,
}
struct NetState {
ch: ch::State<MTU, 4, 4>,
events: Events,
}
@ -116,8 +124,12 @@ impl State {
pub fn new() -> Self {
Self {
ioctl_state: IoctlState::new(),
ch: ch::State::new(),
events: Events::new(),
net: NetState {
ch: ch::State::new(),
events: Events::new(),
},
#[cfg(feature = "bluetooth")]
bt: bluetooth::BtState::new(),
}
}
}
@ -225,21 +237,60 @@ where
PWR: OutputPin,
SPI: SpiBusCyw43,
{
let (ch_runner, device) = ch::new(&mut state.ch, ch::driver::HardwareAddress::Ethernet([0; 6]));
let (ch_runner, device) = ch::new(&mut state.net.ch, ch::driver::HardwareAddress::Ethernet([0; 6]));
let state_ch = ch_runner.state_runner();
let mut runner = Runner::new(ch_runner, Bus::new(pwr, spi), &state.ioctl_state, &state.events);
let mut runner = Runner::new(
ch_runner,
Bus::new(pwr, spi),
&state.ioctl_state,
&state.net.events,
#[cfg(feature = "bluetooth")]
None,
);
runner.init(firmware).await;
runner.init(firmware, None).await;
let control = Control::new(state_ch, &state.net.events, &state.ioctl_state);
(
device,
Control::new(state_ch, &state.events, &state.ioctl_state),
runner,
)
(device, control, runner)
}
fn slice8_mut(x: &mut [u32]) -> &mut [u8] {
let len = x.len() * 4;
unsafe { slice::from_raw_parts_mut(x.as_mut_ptr() as _, len) }
/// Create a new instance of the CYW43 driver.
///
/// Returns a handle to the network device, control handle and a runner for driving the low level
/// stack.
#[cfg(feature = "bluetooth")]
pub async fn new_with_bluetooth<'a, PWR, SPI>(
state: &'a mut State,
pwr: PWR,
spi: SPI,
wifi_firmware: &[u8],
bluetooth_firmware: &[u8],
) -> (
NetDriver<'a>,
bluetooth::BtDriver<'a>,
Control<'a>,
Runner<'a, PWR, SPI>,
)
where
PWR: OutputPin,
SPI: SpiBusCyw43,
{
let (ch_runner, device) = ch::new(&mut state.net.ch, ch::driver::HardwareAddress::Ethernet([0; 6]));
let state_ch = ch_runner.state_runner();
let (bt_runner, bt_driver) = bluetooth::new(&mut state.bt);
let mut runner = Runner::new(
ch_runner,
Bus::new(pwr, spi),
&state.ioctl_state,
&state.net.events,
#[cfg(feature = "bluetooth")]
Some(bt_runner),
);
runner.init(wifi_firmware, Some(bluetooth_firmware)).await;
let control = Control::new(state_ch, &state.net.events, &state.ioctl_state);
(device, bt_driver, control, runner)
}

View File

@ -1,4 +1,4 @@
use embassy_futures::select::{select3, Either3};
use embassy_futures::select::{select4, Either4};
use embassy_net_driver_channel as ch;
use embassy_time::{block_for, Duration, Timer};
use embedded_hal_1::digital::OutputPin;
@ -11,7 +11,8 @@ use crate::fmt::Bytes;
use crate::ioctl::{IoctlState, IoctlType, PendingIoctl};
use crate::nvram::NVRAM;
use crate::structs::*;
use crate::{events, slice8_mut, Core, CHIP, MTU};
use crate::util::slice8_mut;
use crate::{events, Core, CHIP, MTU};
#[cfg(feature = "firmware-logs")]
struct LogState {
@ -36,7 +37,7 @@ impl Default for LogState {
/// Driver communicating with the WiFi chip.
pub struct Runner<'a, PWR, SPI> {
ch: ch::Runner<'a, MTU>,
bus: Bus<PWR, SPI>,
pub(crate) bus: Bus<PWR, SPI>,
ioctl_state: &'a IoctlState,
ioctl_id: u16,
@ -47,6 +48,9 @@ pub struct Runner<'a, PWR, SPI> {
#[cfg(feature = "firmware-logs")]
log: LogState,
#[cfg(feature = "bluetooth")]
pub(crate) bt: Option<crate::bluetooth::BtRunner<'a>>,
}
impl<'a, PWR, SPI> Runner<'a, PWR, SPI>
@ -59,6 +63,7 @@ where
bus: Bus<PWR, SPI>,
ioctl_state: &'a IoctlState,
events: &'a Events,
#[cfg(feature = "bluetooth")] bt: Option<crate::bluetooth::BtRunner<'a>>,
) -> Self {
Self {
ch,
@ -70,33 +75,52 @@ where
events,
#[cfg(feature = "firmware-logs")]
log: LogState::default(),
#[cfg(feature = "bluetooth")]
bt,
}
}
pub(crate) async fn init(&mut self, firmware: &[u8]) {
self.bus.init().await;
pub(crate) async fn init(&mut self, wifi_fw: &[u8], bt_fw: Option<&[u8]>) {
self.bus.init(bt_fw.is_some()).await;
// Init ALP (Active Low Power) clock
debug!("init alp");
self.bus
.write8(FUNC_BACKPLANE, REG_BACKPLANE_CHIP_CLOCK_CSR, BACKPLANE_ALP_AVAIL_REQ)
.await;
debug!("set f2 watermark");
self.bus
.write8(FUNC_BACKPLANE, REG_BACKPLANE_FUNCTION2_WATERMARK, 0x10)
.await;
let watermark = self.bus.read8(FUNC_BACKPLANE, REG_BACKPLANE_FUNCTION2_WATERMARK).await;
debug!("watermark = {:02x}", watermark);
assert!(watermark == 0x10);
debug!("waiting for clock...");
while self.bus.read8(FUNC_BACKPLANE, REG_BACKPLANE_CHIP_CLOCK_CSR).await & BACKPLANE_ALP_AVAIL == 0 {}
debug!("clock ok");
// clear request for ALP
debug!("clear request for ALP");
self.bus.write8(FUNC_BACKPLANE, REG_BACKPLANE_CHIP_CLOCK_CSR, 0).await;
let chip_id = self.bus.bp_read16(0x1800_0000).await;
debug!("chip ID: {}", chip_id);
// Upload firmware.
self.core_disable(Core::WLAN).await;
self.core_disable(Core::SOCSRAM).await; // TODO: is this needed if we reset right after?
self.core_reset(Core::SOCSRAM).await;
// this is 4343x specific stuff: Disable remap for SRAM_3
self.bus.bp_write32(CHIP.socsram_base_address + 0x10, 3).await;
self.bus.bp_write32(CHIP.socsram_base_address + 0x44, 0).await;
let ram_addr = CHIP.atcm_ram_base_address;
debug!("loading fw");
self.bus.bp_write(ram_addr, firmware).await;
self.bus.bp_write(ram_addr, wifi_fw).await;
debug!("loading nvram");
// Round up to 4 bytes.
@ -116,10 +140,23 @@ where
self.core_reset(Core::WLAN).await;
assert!(self.core_is_up(Core::WLAN).await);
// wait until HT clock is available; takes about 29ms
debug!("wait for HT clock");
while self.bus.read8(FUNC_BACKPLANE, REG_BACKPLANE_CHIP_CLOCK_CSR).await & 0x80 == 0 {}
// "Set up the interrupt mask and enable interrupts"
// self.bus.bp_write32(CHIP.sdiod_core_base_address + 0x24, 0xF0).await;
debug!("setup interrupt mask");
self.bus
.bp_write32(CHIP.sdiod_core_base_address + SDIO_INT_HOST_MASK, I_HMB_SW_MASK)
.await;
// Set up the interrupt mask and enable interrupts
if bt_fw.is_some() {
debug!("bluetooth setup interrupt mask");
self.bus
.bp_write32(CHIP.sdiod_core_base_address + SDIO_INT_HOST_MASK, I_HMB_FC_CHANGE)
.await;
}
self.bus
.write16(FUNC_BUS, REG_BUS_INTERRUPT_ENABLE, IRQ_F2_PACKET_AVAILABLE)
@ -128,11 +165,11 @@ where
// "Lower F2 Watermark to avoid DMA Hang in F2 when SD Clock is stopped."
// Sounds scary...
self.bus
.write8(FUNC_BACKPLANE, REG_BACKPLANE_FUNCTION2_WATERMARK, 32)
.write8(FUNC_BACKPLANE, REG_BACKPLANE_FUNCTION2_WATERMARK, SPI_F2_WATERMARK)
.await;
// wait for wifi startup
debug!("waiting for wifi init...");
// wait for F2 to be ready
debug!("waiting for F2 to be ready...");
while self.bus.read32(FUNC_BUS, REG_BUS_STATUS).await & STATUS_F2_RX_READY == 0 {}
// Some random configs related to sleep.
@ -153,19 +190,27 @@ where
*/
// clear pulls
debug!("clear pad pulls");
self.bus.write8(FUNC_BACKPLANE, REG_BACKPLANE_PULL_UP, 0).await;
let _ = self.bus.read8(FUNC_BACKPLANE, REG_BACKPLANE_PULL_UP).await;
// start HT clock
//self.bus.write8(FUNC_BACKPLANE, REG_BACKPLANE_CHIP_CLOCK_CSR, 0x10).await;
//debug!("waiting for HT clock...");
//while self.bus.read8(FUNC_BACKPLANE, REG_BACKPLANE_CHIP_CLOCK_CSR).await & 0x80 == 0 {}
//debug!("clock ok");
self.bus
.write8(FUNC_BACKPLANE, REG_BACKPLANE_CHIP_CLOCK_CSR, 0x10)
.await; // SBSDIO_HT_AVAIL_REQ
debug!("waiting for HT clock...");
while self.bus.read8(FUNC_BACKPLANE, REG_BACKPLANE_CHIP_CLOCK_CSR).await & 0x80 == 0 {}
debug!("clock ok");
#[cfg(feature = "firmware-logs")]
self.log_init().await;
debug!("wifi init done");
#[cfg(feature = "bluetooth")]
if let Some(bt_fw) = bt_fw {
self.bt.as_mut().unwrap().init_bluetooth(&mut self.bus, bt_fw).await;
}
debug!("cyw43 runner init done");
}
#[cfg(feature = "firmware-logs")]
@ -222,7 +267,7 @@ where
}
}
/// Run the
/// Run the CYW43 event handling loop.
pub async fn run(mut self) -> ! {
let mut buf = [0; 512];
loop {
@ -231,11 +276,27 @@ where
if self.has_credit() {
let ioctl = self.ioctl_state.wait_pending();
let tx = self.ch.tx_buf();
let wifi_tx = self.ch.tx_buf();
#[cfg(feature = "bluetooth")]
let bt_tx = async {
match &mut self.bt {
Some(bt) => bt.tx_chan.receive().await,
None => core::future::pending().await,
}
};
#[cfg(not(feature = "bluetooth"))]
let bt_tx = core::future::pending::<()>();
// interrupts aren't working yet for bluetooth. Do busy-polling instead.
// Note for this to work `ev` has to go last in the `select()`. It prefers
// first futures if they're ready, so other select branches don't get starved.`
#[cfg(feature = "bluetooth")]
let ev = core::future::ready(());
#[cfg(not(feature = "bluetooth"))]
let ev = self.bus.wait_for_event();
match select3(ioctl, tx, ev).await {
Either3::First(PendingIoctl {
match select4(ioctl, wifi_tx, bt_tx, ev).await {
Either4::First(PendingIoctl {
buf: iobuf,
kind,
cmd,
@ -244,7 +305,7 @@ where
self.send_ioctl(kind, cmd, iface, unsafe { &*iobuf }, &mut buf).await;
self.check_status(&mut buf).await;
}
Either3::Second(packet) => {
Either4::Second(packet) => {
trace!("tx pkt {:02x}", Bytes(&packet[..packet.len().min(48)]));
let buf8 = slice8_mut(&mut buf);
@ -298,7 +359,11 @@ where
self.ch.tx_done();
self.check_status(&mut buf).await;
}
Either3::Third(()) => {
Either4::Third(_) => {
#[cfg(feature = "bluetooth")]
self.bt.as_mut().unwrap().hci_write(&mut self.bus).await;
}
Either4::Fourth(()) => {
self.handle_irq(&mut buf).await;
}
}
@ -314,17 +379,24 @@ where
async fn handle_irq(&mut self, buf: &mut [u32; 512]) {
// Receive stuff
let irq = self.bus.read16(FUNC_BUS, REG_BUS_INTERRUPT).await;
trace!("irq{}", FormatInterrupt(irq));
if irq != 0 {
trace!("irq{}", FormatInterrupt(irq));
}
if irq & IRQ_F2_PACKET_AVAILABLE != 0 {
self.check_status(buf).await;
}
if irq & IRQ_DATA_UNAVAILABLE != 0 {
// TODO what should we do here?
warn!("IRQ DATA_UNAVAILABLE, clearing...");
// this seems to be ignorable with no ill effects.
trace!("IRQ DATA_UNAVAILABLE, clearing...");
self.bus.write16(FUNC_BUS, REG_BUS_INTERRUPT, 1).await;
}
#[cfg(feature = "bluetooth")]
if let Some(bt) = &mut self.bt {
bt.handle_irq(&mut self.bus).await;
}
}
/// Handle F2 events while status register is set

20
cyw43/src/util.rs Normal file
View File

@ -0,0 +1,20 @@
#![allow(unused)]
use core::slice;
pub(crate) fn slice8_mut(x: &mut [u32]) -> &mut [u8] {
let len = x.len() * 4;
unsafe { slice::from_raw_parts_mut(x.as_mut_ptr() as _, len) }
}
pub(crate) fn is_aligned(a: u32, x: u32) -> bool {
(a & (x - 1)) == 0
}
pub(crate) fn round_down(x: u32, a: u32) -> u32 {
x & !(a - 1)
}
pub(crate) fn round_up(x: u32, a: u32) -> u32 {
((x + a - 1) / a) * a
}

View File

@ -16,8 +16,8 @@ embassy-net = { version = "0.4.0", path = "../../embassy-net", features = ["defm
embassy-net-wiznet = { version = "0.1.0", path = "../../embassy-net-wiznet", features = ["defmt"] }
embassy-futures = { version = "0.1.0", path = "../../embassy-futures" }
embassy-usb-logger = { version = "0.2.0", path = "../../embassy-usb-logger" }
cyw43 = { version = "0.2.0", path = "../../cyw43", features = ["defmt", "firmware-logs"] }
cyw43-pio = { version = "0.2.0", path = "../../cyw43-pio", features = ["defmt", "overclock"] }
cyw43 = { version = "0.2.0", path = "../../cyw43", features = ["defmt", "firmware-logs", "bluetooth"] }
cyw43-pio = { version = "0.2.0", path = "../../cyw43-pio", features = ["defmt"] }
defmt = "0.3"
defmt-rtt = "0.4"
@ -59,9 +59,22 @@ pio = "0.2.1"
rand = { version = "0.8.5", default-features = false }
embedded-sdmmc = "0.7.0"
bt-hci = { version = "0.1.0", default-features = false, features = ["defmt"] }
trouble-host = { version = "0.1.0", features = ["defmt", "gatt"] }
[profile.release]
debug = 2
[profile.dev]
lto = true
opt-level = "z"
[patch.crates-io]
trouble-host = { git = "https://github.com/embassy-rs/trouble.git", rev = "4b8c0f499b34e46ca23a56e2d1640ede371722cf" }
bt-hci = { git = "https://github.com/alexmoon/bt-hci.git", rev = "b9cd5954f6bd89b535cad9c418e9fdf12812d7c3" }
embassy-executor = { path = "../../embassy-executor" }
embassy-sync = { path = "../../embassy-sync" }
embassy-futures = { path = "../../embassy-futures" }
embassy-time = { path = "../../embassy-time" }
embassy-time-driver = { path = "../../embassy-time-driver" }
embassy-embedded-hal = { path = "../../embassy-embedded-hal" }

View File

@ -0,0 +1,148 @@
//! This example test the RP Pico W on board LED.
//!
//! It does not work with the RP Pico board. See blinky.rs.
#![no_std]
#![no_main]
use bt_hci::controller::ExternalController;
use cyw43_pio::PioSpi;
use defmt::*;
use embassy_executor::Spawner;
use embassy_futures::join::join3;
use embassy_rp::bind_interrupts;
use embassy_rp::gpio::{Level, Output};
use embassy_rp::peripherals::{DMA_CH0, PIO0};
use embassy_rp::pio::{InterruptHandler, Pio};
use embassy_sync::blocking_mutex::raw::NoopRawMutex;
use embassy_time::{Duration, Timer};
use static_cell::StaticCell;
use trouble_host::advertise::{AdStructure, Advertisement, BR_EDR_NOT_SUPPORTED, LE_GENERAL_DISCOVERABLE};
use trouble_host::attribute::{AttributeTable, CharacteristicProp, Service, Uuid};
use trouble_host::gatt::GattEvent;
use trouble_host::{Address, BleHost, BleHostResources, PacketQos};
use {defmt_rtt as _, embassy_time as _, panic_probe as _};
bind_interrupts!(struct Irqs {
PIO0_IRQ_0 => InterruptHandler<PIO0>;
});
#[embassy_executor::task]
async fn cyw43_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
runner.run().await
}
#[embassy_executor::main]
async fn main(spawner: Spawner) {
let p = embassy_rp::init(Default::default());
let fw = include_bytes!("../../../../cyw43-firmware/43439A0.bin");
let clm = include_bytes!("../../../../cyw43-firmware/43439A0_clm.bin");
let btfw = include_bytes!("../../../../cyw43-firmware/43439A0_btfw.bin");
// To make flashing faster for development, you may want to flash the firmwares independently
// at hardcoded addresses, instead of baking them into the program with `include_bytes!`:
// probe-rs download 43439A0.bin --format bin --chip RP2040 --base-address 0x10100000
// probe-rs download 43439A0_clm.bin --format bin --chip RP2040 --base-address 0x10140000
//let fw = unsafe { core::slice::from_raw_parts(0x10100000 as *const u8, 224190) };
//let clm = unsafe { core::slice::from_raw_parts(0x10140000 as *const u8, 4752) };
let pwr = Output::new(p.PIN_23, Level::Low);
let cs = Output::new(p.PIN_25, Level::High);
let mut pio = Pio::new(p.PIO0, Irqs);
let spi = PioSpi::new(&mut pio.common, pio.sm0, pio.irq0, cs, p.PIN_24, p.PIN_29, p.DMA_CH0);
static STATE: StaticCell<cyw43::State> = StaticCell::new();
let state = STATE.init(cyw43::State::new());
let (_net_device, bt_device, mut control, runner) = cyw43::new_with_bluetooth(state, pwr, spi, fw, btfw).await;
unwrap!(spawner.spawn(cyw43_task(runner)));
control.init(clm).await;
let controller: ExternalController<_, 10> = ExternalController::new(bt_device);
static HOST_RESOURCES: StaticCell<BleHostResources<4, 32, 27>> = StaticCell::new();
let host_resources = HOST_RESOURCES.init(BleHostResources::new(PacketQos::None));
let mut ble: BleHost<'_, _> = BleHost::new(controller, host_resources);
ble.set_random_address(Address::random([0xff, 0x9f, 0x1a, 0x05, 0xe4, 0xff]));
let mut table: AttributeTable<'_, NoopRawMutex, 10> = AttributeTable::new();
// Generic Access Service (mandatory)
let id = b"Pico W Bluetooth";
let appearance = [0x80, 0x07];
let mut bat_level = [0; 1];
let handle = {
let mut svc = table.add_service(Service::new(0x1800));
let _ = svc.add_characteristic_ro(0x2a00, id);
let _ = svc.add_characteristic_ro(0x2a01, &appearance[..]);
svc.build();
// Generic attribute service (mandatory)
table.add_service(Service::new(0x1801));
// Battery service
let mut svc = table.add_service(Service::new(0x180f));
svc.add_characteristic(
0x2a19,
&[CharacteristicProp::Read, CharacteristicProp::Notify],
&mut bat_level,
)
.build()
};
let mut adv_data = [0; 31];
AdStructure::encode_slice(
&[
AdStructure::Flags(LE_GENERAL_DISCOVERABLE | BR_EDR_NOT_SUPPORTED),
AdStructure::ServiceUuids16(&[Uuid::Uuid16([0x0f, 0x18])]),
AdStructure::CompleteLocalName(b"Pico W Bluetooth"),
],
&mut adv_data[..],
)
.unwrap();
let server = ble.gatt_server(&table);
info!("Starting advertising and GATT service");
let _ = join3(
ble.run(),
async {
loop {
match server.next().await {
Ok(GattEvent::Write { handle, connection: _ }) => {
let _ = table.get(handle, |value| {
info!("Write event. Value written: {:?}", value);
});
}
Ok(GattEvent::Read { .. }) => {
info!("Read event");
}
Err(e) => {
error!("Error processing GATT events: {:?}", e);
}
}
}
},
async {
let mut advertiser = ble
.advertise(
&Default::default(),
Advertisement::ConnectableScannableUndirected {
adv_data: &adv_data[..],
scan_data: &[],
},
)
.await
.unwrap();
let conn = advertiser.accept().await.unwrap();
// Keep connection alive
let mut tick: u8 = 0;
loop {
Timer::after(Duration::from_secs(10)).await;
tick += 1;
server.notify(handle, &conn, &[tick]).await.unwrap();
}
},
)
.await;
}

View File

@ -28,7 +28,7 @@ bind_interrupts!(struct Irqs {
});
#[embassy_executor::task]
async fn wifi_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
async fn cyw43_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
runner.run().await
}
@ -62,7 +62,7 @@ async fn main(spawner: Spawner) {
static STATE: StaticCell<cyw43::State> = StaticCell::new();
let state = STATE.init(cyw43::State::new());
let (net_device, mut control, runner) = cyw43::new(state, pwr, spi, fw).await;
unwrap!(spawner.spawn(wifi_task(runner)));
unwrap!(spawner.spawn(cyw43_task(runner)));
control.init(clm).await;
control

View File

@ -21,7 +21,7 @@ bind_interrupts!(struct Irqs {
});
#[embassy_executor::task]
async fn wifi_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
async fn cyw43_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
runner.run().await
}
@ -46,7 +46,7 @@ async fn main(spawner: Spawner) {
static STATE: StaticCell<cyw43::State> = StaticCell::new();
let state = STATE.init(cyw43::State::new());
let (_net_device, mut control, runner) = cyw43::new(state, pwr, spi, fw).await;
unwrap!(spawner.spawn(wifi_task(runner)));
unwrap!(spawner.spawn(cyw43_task(runner)));
control.init(clm).await;
control

View File

@ -23,7 +23,7 @@ bind_interrupts!(struct Irqs {
});
#[embassy_executor::task]
async fn wifi_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
async fn cyw43_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
runner.run().await
}
@ -56,7 +56,7 @@ async fn main(spawner: Spawner) {
static STATE: StaticCell<cyw43::State> = StaticCell::new();
let state = STATE.init(cyw43::State::new());
let (_net_device, mut control, runner) = cyw43::new(state, pwr, spi, fw).await;
unwrap!(spawner.spawn(wifi_task(runner)));
unwrap!(spawner.spawn(cyw43_task(runner)));
control.init(clm).await;
control

View File

@ -27,11 +27,11 @@ bind_interrupts!(struct Irqs {
PIO0_IRQ_0 => InterruptHandler<PIO0>;
});
const WIFI_NETWORK: &str = "EmbassyTest";
const WIFI_PASSWORD: &str = "V8YxhKt5CdIAJFud";
const WIFI_NETWORK: &str = "LadronDeWifi";
const WIFI_PASSWORD: &str = "MBfcaedHmyRFE4kaQ1O5SsY8";
#[embassy_executor::task]
async fn wifi_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
async fn cyw43_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
runner.run().await
}
@ -65,7 +65,7 @@ async fn main(spawner: Spawner) {
static STATE: StaticCell<cyw43::State> = StaticCell::new();
let state = STATE.init(cyw43::State::new());
let (net_device, mut control, runner) = cyw43::new(state, pwr, spi, fw).await;
unwrap!(spawner.spawn(wifi_task(runner)));
unwrap!(spawner.spawn(cyw43_task(runner)));
control.init(clm).await;
control

View File

@ -34,7 +34,7 @@ const WIFI_NETWORK: &str = "ssid"; // change to your network SSID
const WIFI_PASSWORD: &str = "pwd"; // change to your network password
#[embassy_executor::task]
async fn wifi_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
async fn cyw43_task(runner: cyw43::Runner<'static, Output<'static>, PioSpi<'static, PIO0, 0, DMA_CH0>>) -> ! {
runner.run().await
}
@ -67,7 +67,7 @@ async fn main(spawner: Spawner) {
static STATE: StaticCell<cyw43::State> = StaticCell::new();
let state = STATE.init(cyw43::State::new());
let (net_device, mut control, runner) = cyw43::new(state, pwr, spi, fw).await;
unwrap!(spawner.spawn(wifi_task(runner)));
unwrap!(spawner.spawn(cyw43_task(runner)));
control.init(clm).await;
control