0x00 关于 Pico W 开发板
Pico 开发板推出于 2021 年,Pico W 开发板则是 2022 年。Pico W 在兼容 Pico 引脚布局的基础上,集成了一颗英飞凌 CYW43439 芯片,以提供 WiFi 4(802.11n)和蓝牙 5.2 功能。
对于一个需要联网的嵌入式产品(例如智能水壶、温度湿度传感器)来说,要提供无线功能,我们大致有两种选择:
- 直接使用带无线功能的 MCU 开发,例如 ESP32-C3。成本可低至 10 CNY。
- 使用常规 MCU 完成主要功能,由无线芯片提供网络服务,两者之间通过 UART 或 SPI 等协议通讯。例如 STM32 + ESP8684。
Pico W 方案是后者。这种路线有几个好处:选型时无需在意 wireless SoC 本身的资源(假如采取前一种路线,则可能由于 ESP32-C3 不具有某些外设,而不得不选择 ESP32-S3);无需依赖 ESP-IDF 软件栈(它随时可能大更新);可以方便地更换 MCU 或 wireless SoC 型号,代码移植比较简单。因此,对于 DIY 玩家而言,这种联网方式是比较理想的。
四种开发板中,「W」表示支持无线功能,「H」表示已经预先焊接排阵。顺带一提,H 版并不是在普通版的 pcb 上焊接而成的。从图中可以看出,二者的 pcb 设计有明显区别,且普通版的 swd 接口引脚间距为 2.54mm,而 H 版的 swd 接口则为 JST-SH 端子,间距 1.00mm。
RP2040 与 CYW43439 芯片通过 SPI 连接,用到的 GPIO 口如下:
- GP29 作为 SPI CLK
- GP25 作为 SPI CS
- GP24 作为 SPI data/IRQ
- GP23 作为 power on 信号
这四个 GPIO 在 2021 年的 Pico 开发板上就没有引出,可见当时就已经预留给了 Pico W。在上述四个 GPIO 中,GP29 同时是 ADC3,用于测量 VSYS 电压,如果使用无线功能,则只能等传输间隙才能读取 ADC3。不过我们的应用无需读取这个电压值。
查阅 RP2040 datasheet,我们发现,GP29 在 SPI1 外设中负责 CS# 信号,但现在被用于时钟信号。因此,pico sdk 的无线功能很可能并未使用 SPI 外设,而是采用其他方法驱动。我们后文会分析相关代码。
0x01 点亮 LED
Pico 开发板上的 LED 直接连接到 RP2040 的 GP25,而 Pico W 开发板的 LED 连接到了 CYW43439 芯片的 GPIO 上。我们先试着点亮这颗 LED。
参考 pico-examples 中的代码, CMakeLists.txt
配置如下:
这里引入了 pico_cyw43_arch_none
库,而 blink.c
实现如下:
#include "pico/stdlib.h"
#include "pico/cyw43_arch.h"
int main() {
stdio_init_all();
if (cyw43_arch_init()) {
printf("Wi-Fi init failed");
return -1;
}
while (true) {
cyw43_arch_gpio_put(CYW43_WL_GPIO_LED_PIN, 1);
sleep_ms(250);
cyw43_arch_gpio_put(CYW43_WL_GPIO_LED_PIN, 0);
sleep_ms(250);
}
}
LED 可以正常闪烁,串口消息如下:
Version: 7.95.49 (2271bb6 CY) CRC: b7a28ef3 Date: Mon 2021-11-29 22:50:27 PST Ucode Ver: 1043.2162 FWID 01-c51d9400
cyw43 loaded ok, mac d8:3a:dd:8c:16:98
我们来观察 cyw43 库的代码。GPIO 的设置是通过 cyw43_arch_gpio_put()
执行的,跟进:
void cyw43_arch_gpio_put(uint wl_gpio, bool value) {
invalid_params_if(CYW43_ARCH, wl_gpio >= CYW43_WL_GPIO_COUNT);
cyw43_gpio_set(&cyw43_state, (int)wl_gpio, value);
}
int cyw43_gpio_set(cyw43_t *self, int gpio, bool val) {
CYW43_THREAD_ENTER;
int ret = cyw43_ensure_up(self);
if (ret) {
CYW43_THREAD_EXIT;
return ret;
}
ret = cyw43_ll_gpio_set(&self->cyw43_ll, gpio, val);
CYW43_THREAD_EXIT;
return ret;
}
代码中出现了 CYW43_THREAD_ENTER
和 CYW43_THREAD_EXIT
这两个宏,看看它们的实现:
void cyw43_thread_enter(void) {
async_context_acquire_lock_blocking(cyw43_async_context);
}
void cyw43_thread_exit(void) {
async_context_release_lock(cyw43_async_context);
}
这两个函数的功能就是获取和释放锁。继续看 GPIO 相关代码:
int cyw43_ll_gpio_set(cyw43_ll_t *self_in, int gpio_n, bool gpio_en) {
cyw43_int_t *self = CYW_INT_FROM_LL(self_in);
if (!(gpio_n >= 0 && gpio_n < CYW43_NUM_GPIOS)) {
return -1;
}
CYW43_VDEBUG("cyw43_set_gpio %d=%d\n", gpio_n, gpio_en);
cyw43_write_iovar_u32_u32(self, "gpioout", 1 << gpio_n, gpio_en ? (1 << gpio_n) : 0, WWD_STA_INTERFACE);
return 0;
}
static void cyw43_write_iovar_u32_u32(cyw43_int_t *self, const char *var, uint32_t val0, uint32_t val1, uint32_t iface) {
uint8_t *buf = &self->spid_buf[SDPCM_HEADER_LEN + 16];
size_t len = strlen(var) + 1;
memcpy(buf, var, len);
cyw43_put_le32(buf + len, val0);
cyw43_put_le32(buf + len + 4, val1);
cyw43_do_ioctl(self, SDPCM_SET, WLC_SET_VAR, len + 8, buf, iface);
}
上述代码调用 cyw43_do_ioctl
来发送 8 个字节的信息,分为两个 uint32,即 GPIO mask 和要设置的值。跟进:
// will read the ioctl from buf
// will then write the result (max len bytes) into buf
static int cyw43_do_ioctl(cyw43_int_t *self, uint32_t kind, uint32_t cmd, size_t len, uint8_t *buf, uint32_t iface) {
cyw43_send_ioctl(self, kind, cmd, len, buf, iface);
uint32_t start = cyw43_hal_ticks_us();
while (cyw43_hal_ticks_us() - start < CYW43_IOCTL_TIMEOUT_US) {
size_t res_len;
uint8_t *res_buf;
int ret = cyw43_ll_sdpcm_poll_device(self, &res_len, &res_buf);
if (ret == CONTROL_HEADER) {
#if CYW43_USE_STATS
uint32_t time_us = cyw43_hal_ticks_us() - start;
if (time_us > CYW43_STAT_GET(LONGEST_IOCTL_TIME)) {
CYW43_STAT_SET(LONGEST_IOCTL_TIME, time_us);
}
#endif
// it seems that res_len is always the length of the argument in buf
memmove(buf, res_buf, len < res_len ? len : res_len);
return 0;
} else if (ret == ASYNCEVENT_HEADER) {
cyw43_cb_process_async_event(self, cyw43_ll_parse_async_event(res_len, res_buf));
} else if (ret == DATA_HEADER) {
cyw43_cb_process_ethernet(self->cb_data, res_len >> 31, res_len & 0x7fffffff, res_buf);
} else if (ret >= 0) {
CYW43_WARN("do_ioctl: got unexpected packet %d\n", ret);
}
CYW43_DO_IOCTL_WAIT;
}
CYW43_WARN("do_ioctl(%u, %u, %u): timeout\n", (unsigned int)kind, (unsigned int)cmd, (unsigned int)len);
return CYW43_FAIL_FAST_CHECK(-CYW43_ETIMEDOUT);
}
简而言之,调用 cyw43_send_ioctl()
发送报文,然后等待响应。继续跟进 cyw43_send_ioctl()
函数:
static int cyw43_send_ioctl(cyw43_int_t *self, uint32_t kind, uint32_t cmd, size_t len, const uint8_t *buf, uint32_t iface) {
if (SDPCM_HEADER_LEN + 16 + len > sizeof(self->spid_buf)) {
return CYW43_FAIL_FAST_CHECK(-CYW43_EINVAL);
}
self->wwd_sdpcm_requested_ioctl_id += 1;
uint32_t flags = ((((uint32_t)self->wwd_sdpcm_requested_ioctl_id) << CDCF_IOC_ID_SHIFT) & CDCF_IOC_ID_MASK)
| kind | (iface << CDCF_IOC_IF_SHIFT);
// create header
struct ioctl_header_t *header = (void *)&self->spid_buf[SDPCM_HEADER_LEN];
header->cmd = cmd;
header->len = len & 0xffff;
header->flags = flags;
header->status = 0;
// copy in payload
memcpy(self->spid_buf + SDPCM_HEADER_LEN + 16, buf, len);
// do transfer
CYW43_VDEBUG("Sending cmd %s (%lu) len %lu flags %lu status %lu\n", ioctl_cmd_name(header->cmd), header->cmd, header->len, header->flags, header->status);
if (header->cmd == WLC_SET_VAR || header->cmd == WLC_GET_VAR) {
CYW43_VDEBUG("%s %s\n", ioctl_cmd_name(header->cmd), (const char *)buf);
}
return cyw43_sdpcm_send_common(self, CONTROL_HEADER, 16 + len, self->spid_buf);
}
上述代码的功能是组装好 header 和 payload,装进 spid_buf
,然后调用 cyw43_sdpcm_send_common()
发送之。跟进:
// buf must be writable and have:
// - SDPCM_HEADER_LEN bytes at the start for writing the headers
// - readable data at the end for padding to get to 64 byte alignment
static int cyw43_sdpcm_send_common(cyw43_int_t *self, uint32_t kind, size_t len, uint8_t *buf) {
// validate args
if (kind != CONTROL_HEADER && kind != DATA_HEADER) {
return CYW43_FAIL_FAST_CHECK(-CYW43_EINVAL);
}
cyw43_ll_bus_sleep((void *)self, false);
// Wait until we are allowed to send
// Credits are 8-bit unsigned integers that roll over, so we are stalled while they are equal
if (self->wlan_flow_control || self->wwd_sdpcm_last_bus_data_credit == self->wwd_sdpcm_packet_transmit_sequence_number) {
CYW43_VDEBUG("[CYW43;%u] STALL(%u;%u-%u)\n", (int)cyw43_hal_ticks_ms(), self->wlan_flow_control, self->wwd_sdpcm_packet_transmit_sequence_number, self->wwd_sdpcm_last_bus_data_credit);
// 略
}
size_t size = SDPCM_HEADER_LEN + len;
// create header
struct sdpcm_header_t *header = (void *)&buf[0];
header->size = size;
// ... 略
header->reserved[1] = 0;
self->wwd_sdpcm_packet_transmit_sequence_number += 1;
// padding is taken from junk at end of buffer
return cyw43_write_bytes(self, WLAN_FUNCTION, 0, SDPCM_PAD(size), buf);
}
最终调用的函数是 cyw43_write_bytes()
。看看它的实现:
int cyw43_write_bytes(cyw43_int_t *self, uint32_t fn, uint32_t addr, size_t len, const uint8_t *src) {
assert(fn != BACKPLANE_FUNCTION || (len <= CYW43_BUS_MAX_BLOCK_SIZE));
const size_t aligned_len = (len + 3) & ~3u;
assert(aligned_len > 0 && aligned_len <= 0x7f8);
if (fn == WLAN_FUNCTION) {
// 略
}
if (src == self->spid_buf) { // avoid a copy in the usual case just to add the header
self->spi_header[(CYW43_BACKPLANE_READ_PAD_LEN_BYTES / 4)] = make_cmd(true, true, fn, addr, len);
logic_debug_set(pin_WIFI_TX, 1);
int res = cyw43_spi_transfer(self, (uint8_t *)&self->spi_header[(CYW43_BACKPLANE_READ_PAD_LEN_BYTES / 4)], aligned_len + 4, NULL, 0);
logic_debug_set(pin_WIFI_TX, 0);
return res;
} else {
// todo: would be nice to get rid of this. Only used for firmware download?
assert(src < self->spid_buf || src >= (self->spid_buf + sizeof(self->spid_buf)));
self->spi_header[(CYW43_BACKPLANE_READ_PAD_LEN_BYTES / 4)] = make_cmd(true, true, fn, addr, len);
memcpy(self->spid_buf, src, len);
return cyw43_spi_transfer(self, (uint8_t *)&self->spi_header[(CYW43_BACKPLANE_READ_PAD_LEN_BYTES / 4)], aligned_len + 4, NULL, 0);
}
}
看来,具体的 SPI 传输是由 cyw43_spi_transfer()
完成的。跟进:
int cyw43_spi_transfer(cyw43_int_t *self, const uint8_t *tx, size_t tx_length, uint8_t *rx,
size_t rx_length) {
if ((tx == NULL) && (rx == NULL)) {
return CYW43_FAIL_FAST_CHECK(-CYW43_EINVAL);
}
bus_data_t *bus_data = (bus_data_t *)self->bus_data;
start_spi_comms(self);
if (rx != NULL) {
if (tx == NULL) {
tx = rx;
assert(tx_length && tx_length < rx_length);
}
DUMP_SPI_TRANSACTIONS(
printf("[%lu] bus TX/RX %u bytes rx %u:", counter++, tx_length, rx_length);
dump_bytes(tx, tx_length);
)
assert(!(tx_length & 3));
assert(!(((uintptr_t)tx) & 3));
assert(!(((uintptr_t)rx) & 3));
assert(!(rx_length & 3));
pio_sm_set_enabled(bus_data->pio, bus_data->pio_sm, false);
pio_sm_set_wrap(bus_data->pio, bus_data->pio_sm, bus_data->pio_offset, bus_data->pio_offset + SPI_OFFSET_END - 1);
pio_sm_clear_fifos(bus_data->pio, bus_data->pio_sm);
pio_sm_set_pindirs_with_mask(bus_data->pio, bus_data->pio_sm, 1u << DATA_OUT_PIN, 1u << DATA_OUT_PIN);
pio_sm_restart(bus_data->pio, bus_data->pio_sm);
pio_sm_clkdiv_restart(bus_data->pio, bus_data->pio_sm);
pio_sm_put(bus_data->pio, bus_data->pio_sm, tx_length * 8 - 1);
pio_sm_exec(bus_data->pio, bus_data->pio_sm, pio_encode_out(pio_x, 32));
pio_sm_put(bus_data->pio, bus_data->pio_sm, (rx_length - tx_length) * 8 - 1);
pio_sm_exec(bus_data->pio, bus_data->pio_sm, pio_encode_out(pio_y, 32));
pio_sm_exec(bus_data->pio, bus_data->pio_sm, pio_encode_jmp(bus_data->pio_offset));
dma_channel_abort(bus_data->dma_out);
dma_channel_abort(bus_data->dma_in);
dma_channel_config out_config = dma_channel_get_default_config(bus_data->dma_out);
channel_config_set_bswap(&out_config, true);
channel_config_set_dreq(&out_config, pio_get_dreq(bus_data->pio, bus_data->pio_sm, true));
dma_channel_configure(bus_data->dma_out, &out_config, &bus_data->pio->txf[bus_data->pio_sm], tx, tx_length / 4, true);
dma_channel_config in_config = dma_channel_get_default_config(bus_data->dma_in);
channel_config_set_bswap(&in_config, true);
channel_config_set_dreq(&in_config, pio_get_dreq(bus_data->pio, bus_data->pio_sm, false));
channel_config_set_write_increment(&in_config, true);
channel_config_set_read_increment(&in_config, false);
dma_channel_configure(bus_data->dma_in, &in_config, rx + tx_length, &bus_data->pio->rxf[bus_data->pio_sm], rx_length / 4 - tx_length / 4, true);
pio_sm_set_enabled(bus_data->pio, bus_data->pio_sm, true);
__compiler_memory_barrier();
dma_channel_wait_for_finish_blocking(bus_data->dma_out);
dma_channel_wait_for_finish_blocking(bus_data->dma_in);
__compiler_memory_barrier();
memset(rx, 0, tx_length); // make sure we don't have garbage in what would have been returned data if using real SPI
} else if (tx != NULL) {
DUMP_SPI_TRANSACTIONS(
printf("[%lu] bus TX only %u bytes:", counter++, tx_length);
dump_bytes(tx, tx_length);
)
assert(!(((uintptr_t)tx) & 3));
assert(!(tx_length & 3));
pio_sm_set_enabled(bus_data->pio, bus_data->pio_sm, false);
pio_sm_set_wrap(bus_data->pio, bus_data->pio_sm, bus_data->pio_offset, bus_data->pio_offset + SPI_OFFSET_LP1_END - 1);
pio_sm_clear_fifos(bus_data->pio, bus_data->pio_sm);
pio_sm_set_pindirs_with_mask(bus_data->pio, bus_data->pio_sm, 1u << DATA_OUT_PIN, 1u << DATA_OUT_PIN);
pio_sm_restart(bus_data->pio, bus_data->pio_sm);
pio_sm_clkdiv_restart(bus_data->pio, bus_data->pio_sm);
pio_sm_put(bus_data->pio, bus_data->pio_sm, tx_length * 8 - 1);
pio_sm_exec(bus_data->pio, bus_data->pio_sm, pio_encode_out(pio_x, 32));
pio_sm_put(bus_data->pio, bus_data->pio_sm, 0);
pio_sm_exec(bus_data->pio, bus_data->pio_sm, pio_encode_out(pio_y, 32));
pio_sm_exec(bus_data->pio, bus_data->pio_sm, pio_encode_jmp(bus_data->pio_offset));
dma_channel_abort(bus_data->dma_out);
dma_channel_config out_config = dma_channel_get_default_config(bus_data->dma_out);
channel_config_set_bswap(&out_config, true);
channel_config_set_dreq(&out_config, pio_get_dreq(bus_data->pio, bus_data->pio_sm, true));
dma_channel_configure(bus_data->dma_out, &out_config, &bus_data->pio->txf[bus_data->pio_sm], tx, tx_length / 4, true);
uint32_t fdebug_tx_stall = 1u << (PIO_FDEBUG_TXSTALL_LSB + bus_data->pio_sm);
bus_data->pio->fdebug = fdebug_tx_stall;
pio_sm_set_enabled(bus_data->pio, bus_data->pio_sm, true);
while (!(bus_data->pio->fdebug & fdebug_tx_stall)) {
tight_loop_contents(); // todo timeout
}
__compiler_memory_barrier();
pio_sm_set_enabled(bus_data->pio, bus_data->pio_sm, false);
pio_sm_set_consecutive_pindirs(bus_data->pio, bus_data->pio_sm, DATA_IN_PIN, 1, false);
} else if (rx != NULL) { /* currently do one at a time */
DUMP_SPI_TRANSACTIONS(
printf("[%lu] bus TX %u bytes:", counter++, rx_length);
dump_bytes(rx, rx_length);
)
panic_unsupported();
}
pio_sm_exec(bus_data->pio, bus_data->pio_sm, pio_encode_mov(pio_pins, pio_null)); // for next time we turn output on
stop_spi_comms();
DUMP_SPI_TRANSACTIONS(
printf("RXed:");
dump_bytes(rx, rx_length);
printf("\n");
)
return 0;
}
至此,我们解决了本文 0x00 节提出的「SPI 通讯由谁来完成」的问题。pico sdk 既没有使用 SPI 外设,也没有做 bit banging,而是采用 PIO + DMA 来完成数据传输。如果这次传输是读取数据,则调用 dma_channel_wait_for_finish_blocking()
阻塞 cpu,等待传输完成;如果是发送数据,则轮询等待,直到 FDEBUG
寄存器的 TXSTALL
值不为 0(表示 tx fifo 中的数据已经发送完毕)。综上所述,尽管 pico sdk 采用了 PIO + DMA,但 cpu 仍然会在 spi 传输过程中阻塞。
在 CMakeLists.txt
中,我们链接了 pico_cyw43_arch_none
库,现在详细讨论一番。根据文档,IP 支持是由 lwIP 库提供的,其基础 API 总是可以调用,但是一些高级 API 需要在 FreeRTOS 内使用。在 CMake 中,pico_lwip
库即为刚刚提到的 lwIP;pico_cyw43_driver
是 CYW43439 的驱动;pico_async_context
用于通过各种方式(轮询,多核,或 FreeRTOS)访问非线程安全的 API。
这些底层库被集成到了一些高层库中,我们在 CMake 中一般使用以下之一:
pico_cyw43_arch_lwip_poll
:用于在 Pico W 上以单核轮询方式访问 lwIP,此时NO_SYS=1
;pico_cyw43_arch_threadsafe_background
:用于在 Pico W 上以单核或多核访问 lwIP,但采用 irq 而非轮询处理 lwIP 的回调,此时NO_SYS=1
;pico_cyw43_arch_lwip_sys_freertos
:用于在 FreeRTOS 中访问 lwIP。此时NO_SYS=0
;pico_cyw43_arch_none
:不使用 lwIP,只操控 LED。
详细注释见 pico sdk 的 src/rp2_common/pico_cyw43_arch/include/pico/cyw43_arch.h
。
0x02 扫描 WiFi
我们跑一遍 pico-examples 中的扫描 WiFi 项目。先看 CMake 配置:
add_executable(picow_wifi_scan_background
picow_wifi_scan.c
)
target_include_directories(picow_wifi_scan_background PRIVATE
${CMAKE_CURRENT_LIST_DIR}
${CMAKE_CURRENT_LIST_DIR}/.. # for our common lwipopts
)
target_link_libraries(picow_wifi_scan_background
pico_cyw43_arch_lwip_threadsafe_background
pico_stdlib
)
pico_add_extra_outputs(picow_wifi_scan_background)
add_executable(picow_wifi_scan_poll
picow_wifi_scan.c
)
target_include_directories(picow_wifi_scan_poll PRIVATE
${CMAKE_CURRENT_LIST_DIR}
${CMAKE_CURRENT_LIST_DIR}/.. # for our common lwipopts
)
target_link_libraries(picow_wifi_scan_poll
pico_cyw43_arch_lwip_poll
pico_stdlib
)
pico_add_extra_outputs(picow_wifi_scan_poll)
这份 CMake 文件指定了两个构建目标,其中一个链接 pico_cyw43_arch_lwip_threadsafe_background
库,另一个链接 pico_cyw43_arch_lwip_poll
库。代码如下:
/**
* Copyright (c) 2022 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico/stdlib.h"
#include "pico/cyw43_arch.h"
static int scan_result(void *env, const cyw43_ev_scan_result_t *result) {
if (result) {
printf("ssid: %-32s rssi: %4d chan: %3d mac: %02x:%02x:%02x:%02x:%02x:%02x sec: %u\n",
result->ssid, result->rssi, result->channel,
result->bssid[0], result->bssid[1], result->bssid[2], result->bssid[3], result->bssid[4], result->bssid[5],
result->auth_mode);
}
return 0;
}
#include "hardware/vreg.h"
#include "hardware/clocks.h"
int main() {
stdio_init_all();
if (cyw43_arch_init()) {
printf("failed to initialise\n");
return 1;
}
cyw43_arch_enable_sta_mode();
absolute_time_t scan_time = nil_time;
bool scan_in_progress = false;
while(true) {
if (absolute_time_diff_us(get_absolute_time(), scan_time) < 0) {
if (!scan_in_progress) {
cyw43_wifi_scan_options_t scan_options = {0};
int err = cyw43_wifi_scan(&cyw43_state, &scan_options, NULL, scan_result);
if (err == 0) {
printf("\nPerforming wifi scan\n");
scan_in_progress = true;
} else {
printf("Failed to start scan: %d\n", err);
scan_time = make_timeout_time_ms(10000); // wait 10s and scan again
}
} else if (!cyw43_wifi_scan_active(&cyw43_state)) {
scan_time = make_timeout_time_ms(10000); // wait 10s and scan again
scan_in_progress = false;
}
}
// the following #ifdef is only here so this same example can be used in multiple modes;
// you do not need it in your code
#if PICO_CYW43_ARCH_POLL
// if you are using pico_cyw43_arch_poll, then you must poll periodically from your
// main loop (not from a timer) to check for Wi-Fi driver or lwIP work that needs to be done.
cyw43_arch_poll();
// you can poll as often as you like, however if you have nothing else to do you can
// choose to sleep until either a specified time, or cyw43_arch_poll() has work to do:
cyw43_arch_wait_for_work_until(scan_time);
#else
// if you are not using pico_cyw43_arch_poll, then WiFI driver and lwIP work
// is done via interrupt in the background. This sleep is just an example of some (blocking)
// work you might be doing.
sleep_ms(1000);
#endif
}
cyw43_arch_deinit();
return 0;
}
总结上述代码的工作流程:
- 调用
cyw43_arch_init()
初始化 CYW43439 芯片; - 调用
cyw43_arch_enable_sta_mode()
使其进入 STA 模式; - 若目前并未在扫描,则调用
cyw43_wifi_scan()
;
若目前正在扫描,且cyw43_wifi_scan_active()
返回 0(表示扫描完成),则在 10s 之后再次扫描; - 如果有
PICO_CYW43_ARCH_POLL
,则调用cyw43_arch_poll()
和cyw43_arch_wait_for_work_until(scan_time)
。
这份代码在 poll 模式和 background 模式下都能跑通,不过,poll 模式下需要手动调用 cyw43_arch_poll()
处理任务。
以上,我们跑通了 Pico W 开发板的 WiFi 功能。pico-examples 中还有 TCP、DHCP 等应用的示例,不过代码普遍十分复杂(令笔者回想起数年前在 UDP 信道上编写可靠文件传输服务的经历)。树莓派文档中推荐使用 MicroPython 来进行网络相关编程,本系列文章接下来会讨论 MicroPython 的使用。