cyw43: bluetooth module that almost works
This commit is contained in:
parent
6babd5752e
commit
8d588f0abd
BIN
cyw43-firmware/43439A0.bin
Executable file → Normal file
BIN
cyw43-firmware/43439A0.bin
Executable file → Normal file
Binary file not shown.
BIN
cyw43-firmware/43439A0_btfw.bin
Normal file
BIN
cyw43-firmware/43439A0_btfw.bin
Normal file
Binary file not shown.
BIN
cyw43-firmware/43439A0_clm.bin
Executable file → Normal file
BIN
cyw43-firmware/43439A0_clm.bin
Executable file → Normal file
Binary file not shown.
230
cyw43/src/bluetooth.rs
Normal file
230
cyw43/src/bluetooth.rs
Normal file
@ -0,0 +1,230 @@
|
||||
use embassy_time::{Timer, Duration};
|
||||
use embedded_hal_1::digital::OutputPin;
|
||||
|
||||
use crate::{consts::*, CHIP, bus::Bus, SpiBusCyw43};
|
||||
|
||||
#[derive(Debug)]
|
||||
pub(crate) struct CybtFwCb<'a> {
|
||||
pub p_fw_mem_start: &'a [u8],
|
||||
pub fw_len: u32,
|
||||
pub p_next_line_start: &'a [u8],
|
||||
}
|
||||
|
||||
#[derive(Debug)]
|
||||
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 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 cybt_fw_get_data(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
|
||||
}
|
||||
|
||||
pub(crate) async fn upload_bluetooth_firmware<PWR: OutputPin, SPI: SpiBusCyw43>(bus: &mut Bus<PWR, SPI>, 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..];
|
||||
// buffer
|
||||
let mut data_buffer: [u8; 0x100] = [0; 0x100];
|
||||
// structs
|
||||
let mut btfw_cb = CybtFwCb {
|
||||
p_fw_mem_start: firmware,
|
||||
fw_len: firmware.len() as u32,
|
||||
p_next_line_start: firmware,
|
||||
};
|
||||
let mut hfd = HexFileData {
|
||||
addr_mode: BTFW_ADDR_MODE_UNKNOWN,
|
||||
hi_addr: 0,
|
||||
dest_addr: 0,
|
||||
p_ds: &mut data_buffer,
|
||||
};
|
||||
loop {
|
||||
let mut aligned_data_buffer: [u8; 0x100] = [0; 0x100];
|
||||
let num_fw_bytes = cybt_fw_get_data(&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 !is_aligned(dest_start_addr, 4) {
|
||||
let num_pad_bytes = dest_start_addr % 4;
|
||||
let padded_dest_start_addr = round_down(dest_start_addr, 4);
|
||||
let mut memory_value_bytes = [0; 4];
|
||||
bus.bp_read(padded_dest_start_addr, &mut memory_value_bytes).await;
|
||||
// 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 !is_aligned(dest_end_addr, 4) {
|
||||
let offset = dest_end_addr % 4;
|
||||
let num_pad_bytes_end = 4 - offset;
|
||||
let padded_dest_end_addr = round_down(dest_end_addr, 4);
|
||||
let mut memory_value_bytes = [0; 4];
|
||||
bus.bp_read(padded_dest_end_addr, &mut memory_value_bytes).await;
|
||||
// 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];
|
||||
debug!("upload_bluetooth_firmware: dest_start_addr = {:x} dest_end_addr = {:x} aligned_data_buffer_index = {} buffer_to_write = {:02x}", dest_start_addr, dest_end_addr, aligned_data_buffer_index, buffer_to_write);
|
||||
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<PWR: OutputPin, SPI: SpiBusCyw43>(bus: &mut Bus<PWR, SPI>) {
|
||||
debug!("wait_bt_ready");
|
||||
let mut success = false;
|
||||
for _ in 0..300 {
|
||||
let val = bus.bp_read32(BT_CTRL_REG_ADDR).await;
|
||||
// TODO: do we need to swap endianness on this read?
|
||||
debug!("BT_CTRL_REG_ADDR = {:08x}", val);
|
||||
/*if val & BTSDIO_REG_FW_RDY_BITMASK != 0 {
|
||||
break;
|
||||
}*/
|
||||
// TODO: should be 00000000 until it is 0x01000100
|
||||
if val == 0x01000100 {
|
||||
success = true;
|
||||
break;
|
||||
}
|
||||
Timer::after(Duration::from_millis(1)).await;
|
||||
}
|
||||
assert!(success == true);
|
||||
}
|
||||
|
||||
pub(crate) async fn wait_bt_awake<PWR: OutputPin, SPI: SpiBusCyw43>(bus: &mut Bus<PWR, SPI>) {
|
||||
debug!("wait_bt_awake");
|
||||
loop {
|
||||
let val = bus.bp_read32(BT_CTRL_REG_ADDR).await;
|
||||
// TODO: do we need to swap endianness on this read?
|
||||
debug!("BT_CTRL_REG_ADDR = {:08x}", val);
|
||||
if val & BTSDIO_REG_BT_AWAKE_BITMASK != 0 {
|
||||
break;
|
||||
}
|
||||
Timer::after(Duration::from_millis(100)).await;
|
||||
}
|
||||
}
|
||||
|
||||
pub(crate) async fn bt_set_host_ready<PWR: OutputPin, SPI: SpiBusCyw43>(bus: &mut Bus<PWR, SPI>) {
|
||||
debug!("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;
|
||||
}
|
||||
|
||||
pub(crate) async fn bt_set_awake<PWR: OutputPin, SPI: SpiBusCyw43>(bus: &mut Bus<PWR, SPI>) {
|
||||
debug!("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 = old_val | BTSDIO_REG_WAKE_BT_BITMASK;
|
||||
bus.bp_write32(HOST_CTRL_REG_ADDR, new_val).await;
|
||||
}
|
||||
|
||||
pub(crate) async fn bt_toggle_intr<PWR: OutputPin, SPI: SpiBusCyw43>(bus: &mut Bus<PWR, SPI>) {
|
||||
debug!("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;
|
||||
}
|
||||
|
||||
pub(crate) async fn bt_set_intr<PWR: OutputPin, SPI: SpiBusCyw43>(bus: &mut Bus<PWR, SPI>) {
|
||||
debug!("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_bluetooth<PWR: OutputPin, SPI: SpiBusCyw43>(bus: &mut Bus<PWR, SPI>, firmware: &[u8]) {
|
||||
bus.bp_write32(CHIP.bluetooth_base_address + BT2WLAN_PWRUP_ADDR, BT2WLAN_PWRUP_WAKE).await;
|
||||
upload_bluetooth_firmware(bus, firmware).await;
|
||||
wait_bt_ready(bus).await;
|
||||
// TODO: cybt_init_buffer();
|
||||
wait_bt_awake(bus).await;
|
||||
bt_set_host_ready(bus).await;
|
||||
bt_toggle_intr(bus).await;
|
||||
}
|
@ -50,11 +50,13 @@ where
|
||||
|
||||
pub async fn init(&mut self) {
|
||||
// Reset
|
||||
debug!("WL_REG off/on");
|
||||
self.pwr.set_low().unwrap();
|
||||
Timer::after(Duration::from_millis(20)).await;
|
||||
self.pwr.set_high().unwrap();
|
||||
Timer::after(Duration::from_millis(250)).await;
|
||||
|
||||
debug!("read REG_BUS_TEST_RO");
|
||||
while self
|
||||
.read32_swapped(REG_BUS_TEST_RO)
|
||||
.inspect(|v| trace!("{:#x}", v))
|
||||
@ -62,30 +64,56 @@ where
|
||||
!= FEEDBEAD
|
||||
{}
|
||||
|
||||
debug!("write REG_BUS_TEST_RW");
|
||||
self.write32_swapped(REG_BUS_TEST_RW, TEST_PATTERN).await;
|
||||
let val = self.read32_swapped(REG_BUS_TEST_RW).await;
|
||||
trace!("{:#x}", val);
|
||||
assert_eq!(val, TEST_PATTERN);
|
||||
|
||||
debug!("read REG_BUS_CTRL");
|
||||
let val = self.read32_swapped(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 | ENDIAN_BIG | HIGH_SPEED_MODE | INTERRUPT_POLARITY_HIGH | WAKE_UP | 0x4 << (8 * SPI_RESPONSE_DELAY) | INTR_WITH_STATUS << (8 * SPI_STATUS_ENABLE);
|
||||
debug!("write REG_BUS_CTRL");
|
||||
self.write32_swapped(
|
||||
REG_BUS_CTRL,
|
||||
WORD_LENGTH_32 | HIGH_SPEED | INTERRUPT_HIGH | WAKE_UP | STATUS_ENABLE | INTERRUPT_WITH_STATUS,
|
||||
)
|
||||
.await;
|
||||
|
||||
debug!("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
|
||||
debug!("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
|
||||
debug!("read REG_BUS_TEST_RW");
|
||||
let val = self.read32(FUNC_BUS, REG_BUS_TEST_RW).await;
|
||||
trace!("{:#x}", val);
|
||||
assert_eq!(val, TEST_PATTERN);
|
||||
|
||||
// TODO: setting this causes total failure (watermark read test fails)
|
||||
debug!("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)
|
||||
debug!("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
|
||||
debug!("enable a selection of interrupts");
|
||||
self.write16(FUNC_BUS, REG_BUS_INTERRUPT_ENABLE, 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 | IRQ_F1_INTR)
|
||||
.await;
|
||||
}
|
||||
|
||||
pub async fn wlan_read(&mut self, buf: &mut [u32], len_in_u8: u32) {
|
||||
|
@ -51,6 +51,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;
|
||||
@ -118,6 +125,35 @@ pub(crate) const WPA2_SECURITY: u32 = 0x00400000;
|
||||
pub(crate) const MIN_PSK_LEN: usize = 8;
|
||||
pub(crate) const MAX_PSK_LEN: usize = 64;
|
||||
|
||||
// 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 CYW43_BACKPLANE_READ_PAD_LEN_BYTES: u8 = 16;
|
||||
|
||||
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;
|
||||
|
||||
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);
|
||||
|
||||
// Security type (authentication and encryption types are combined using bit mask)
|
||||
#[allow(non_camel_case_types)]
|
||||
#[derive(Copy, Clone, PartialEq)]
|
||||
|
@ -8,6 +8,7 @@
|
||||
pub(crate) mod fmt;
|
||||
|
||||
mod bus;
|
||||
mod bluetooth;
|
||||
mod consts;
|
||||
mod countries;
|
||||
mod events;
|
||||
@ -55,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,
|
||||
@ -82,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,
|
||||
@ -211,6 +214,7 @@ pub async fn new<'a, PWR, SPI>(
|
||||
pwr: PWR,
|
||||
spi: SPI,
|
||||
firmware: &[u8],
|
||||
bluetooth_firmware: &[u8]
|
||||
) -> (NetDriver<'a>, Control<'a>, Runner<'a, PWR, SPI>)
|
||||
where
|
||||
PWR: OutputPin,
|
||||
@ -221,7 +225,7 @@ where
|
||||
|
||||
let mut runner = Runner::new(ch_runner, Bus::new(pwr, spi), &state.ioctl_state, &state.events);
|
||||
|
||||
runner.init(firmware).await;
|
||||
runner.init(firmware, bluetooth_firmware).await;
|
||||
|
||||
(
|
||||
device,
|
||||
|
@ -6,7 +6,7 @@ use embedded_hal_1::digital::OutputPin;
|
||||
|
||||
use crate::bus::Bus;
|
||||
pub use crate::bus::SpiBusCyw43;
|
||||
use crate::consts::*;
|
||||
use crate::{consts::*, bluetooth};
|
||||
use crate::events::{Event, Events, Status};
|
||||
use crate::fmt::Bytes;
|
||||
use crate::ioctl::{IoctlState, IoctlType, PendingIoctl};
|
||||
@ -73,23 +73,41 @@ where
|
||||
}
|
||||
}
|
||||
|
||||
pub(crate) async fn init(&mut self, firmware: &[u8]) {
|
||||
pub(crate) async fn init(&mut self, firmware: &[u8], bluetooth_firmware: &[u8]) {
|
||||
self.bus.init().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;
|
||||
|
||||
// check we can set the bluetooth watermark
|
||||
debug!("set bluetooth 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;
|
||||
|
||||
@ -98,6 +116,9 @@ where
|
||||
debug!("loading fw");
|
||||
self.bus.bp_write(ram_addr, firmware).await;
|
||||
|
||||
debug!("loading bluetooth fw");
|
||||
bluetooth::init_bluetooth(&mut self.bus, bluetooth_firmware).await;
|
||||
|
||||
debug!("loading nvram");
|
||||
// Round up to 4 bytes.
|
||||
let nvram_len = (NVRAM.len() + 3) / 4 * 4;
|
||||
@ -116,23 +137,31 @@ 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;
|
||||
|
||||
self.bus
|
||||
// Set up the interrupt mask and enable interrupts
|
||||
debug!("bluetooth setup interrupt mask");
|
||||
self.bus.bp_write32(CHIP.sdiod_core_base_address + SDIO_INT_HOST_MASK, I_HMB_FC_CHANGE).await;
|
||||
|
||||
// TODO: turn interrupts on here or in bus.init()?
|
||||
/*self.bus
|
||||
.write16(FUNC_BUS, REG_BUS_INTERRUPT_ENABLE, IRQ_F2_PACKET_AVAILABLE)
|
||||
.await;
|
||||
.await;*/
|
||||
|
||||
// "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,14 +182,15 @@ 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;
|
||||
|
@ -32,6 +32,7 @@ async fn wifi_task(
|
||||
async fn main(spawner: Spawner) {
|
||||
let p = embassy_rp::init(Default::default());
|
||||
let fw = include_bytes!("../../../../cyw43-firmware/43439A0.bin");
|
||||
let bt_fw = include_bytes!("../../../../cyw43-firmware/43439A0_btfw.bin");
|
||||
let clm = include_bytes!("../../../../cyw43-firmware/43439A0_clm.bin");
|
||||
|
||||
// To make flashing faster for development, you may want to flash the firmwares independently
|
||||
@ -47,7 +48,7 @@ async fn main(spawner: Spawner) {
|
||||
let spi = PioSpi::new(&mut pio.common, pio.sm0, pio.irq0, cs, p.PIN_24, p.PIN_29, p.DMA_CH0);
|
||||
|
||||
let state = make_static!(cyw43::State::new());
|
||||
let (_net_device, mut control, runner) = cyw43::new(state, pwr, spi, fw).await;
|
||||
let (_net_device, mut control, runner) = cyw43::new(state, pwr, spi, fw, bt_fw).await;
|
||||
unwrap!(spawner.spawn(wifi_task(runner)));
|
||||
|
||||
control.init(clm).await;
|
||||
|
Loading…
Reference in New Issue
Block a user