1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 04:15:44 +03:00

Adding RP2350 SDK and target framework (#13988)

* Adding RP2350 SDK and target framework

* Spacing

* Removing board definitions
This commit is contained in:
J Blackman 2024-10-23 10:02:48 +11:00 committed by GitHub
parent 462cb05930
commit 2dd6f95aad
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
576 changed files with 435012 additions and 0 deletions

View file

@ -0,0 +1,30 @@
“BlueKitchen” shall refer to BlueKitchen GmbH.
“Raspberry Pi” shall refer to Raspberry Pi Ltd.
“Product” shall refer to Raspberry Pi hardware products Raspberry Pi Pico W or Raspberry Pi Pico WH.
“Customer” means any purchaser of a Product.
“Customer Products” means products manufactured or distributed by Customers which use or are derived from Products.
Raspberry Pi grants to the Customer a non-exclusive, non-transferable, non-sublicensable, irrevocable, perpetual
and worldwide licence to use, copy, store, develop, modify, and transmit BTstack in order to use BTstack with or
integrate BTstack into Products or Customer Products, and distribute BTstack as part of these Products or
Customer Products or their related documentation or SDKs.
All use of BTstack by the Customer is limited to Products or Customer Products, and the Customer represents and
warrants that all such use shall be in compliance with the terms of this licence and all applicable laws and
regulations, including but not limited to, copyright and other intellectual property laws and privacy regulations.
BlueKitchen retains all rights, title and interest in, to and associated with BTstack and associated websites.
Customer shall not take any action inconsistent with BlueKitchens ownership of BTstack, any associated services,
websites and related content.
There are no implied licences under the terms set forth in this licence, and any rights not expressly granted
hereunder are reserved by BlueKitchen.
BTSTACK IS PROVIDED BY RASPBERRY PI "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED TO THE FULLEST EXTENT
PERMISSIBLE UNDER APPLICABLE LAW. IN NO EVENT SHALL RASPBERRY PI OR BLUEKITCHEN BE LIABLE FOR ANY DIRECT, INDIRECT,
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE
GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
OUT OF THE USE OF BTSTACK, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

View file

@ -0,0 +1,197 @@
load("@pico-sdk//bazel:defs.bzl", "incompatible_with_config")
package(default_visibility = ["//visibility:public"])
_DISABLE_WARNINGS = [
"-Wno-cast-qual",
"-Wno-format",
"-Wno-maybe-uninitialized",
"-Wno-null-dereference",
"-Wno-sign-compare",
"-Wno-stringop-overflow",
"-Wno-suggest-attribute=format",
"-Wno-type-limits",
"-Wno-unused-parameter",
]
cc_library(
name = "pico_btstack_base",
srcs = [
"3rd-party/md5/md5.c",
"3rd-party/micro-ecc/uECC.c",
"3rd-party/rijndael/rijndael.c",
"3rd-party/segger-rtt/SEGGER_RTT.c",
"3rd-party/segger-rtt/SEGGER_RTT_printf.c",
"3rd-party/yxml/yxml.c",
"platform/embedded/btstack_tlv_flash_bank.c",
"platform/embedded/hci_dump_embedded_stdout.c",
"platform/embedded/hci_dump_segger_rtt_stdout.c",
"src/ad_parser.c",
"src/btstack_audio.c",
"src/btstack_base64_decoder.c",
"src/btstack_crypto.c",
"src/btstack_hid_parser.c",
"src/btstack_linked_list.c",
"src/btstack_memory.c",
"src/btstack_memory_pool.c",
"src/btstack_resample.c",
"src/btstack_ring_buffer.c",
"src/btstack_run_loop.c",
"src/btstack_run_loop_base.c",
"src/btstack_slip.c",
"src/btstack_tlv.c",
"src/btstack_tlv_none.c",
"src/btstack_util.c",
"src/hci.c",
"src/hci_cmd.c",
"src/hci_dump.c",
"src/hci_event.c",
"src/l2cap.c",
"src/l2cap_signaling.c",
"src/mesh/gatt-service/mesh_provisioning_service_server.c",
"src/mesh/gatt-service/mesh_proxy_service_server.c",
],
hdrs = glob(["**/*.h"]),
copts = _DISABLE_WARNINGS,
includes = [
".",
"3rd-party/md5",
"3rd-party/micro-ecc",
"3rd-party/rijndael",
"3rd-party/segger-rtt",
"3rd-party/yxml",
"platform/embedded",
"src",
],
target_compatible_with = incompatible_with_config(
"@pico-sdk//bazel/constraint:pico_btstack_config_unset",
),
deps = ["@pico-sdk//bazel/config:PICO_BTSTACK_CONFIG"],
)
cc_library(
name = "pico_btstack_ble",
srcs = [
"src/ble/att_db.c",
"src/ble/att_db_util.c",
"src/ble/att_dispatch.c",
"src/ble/att_server.c",
"src/ble/gatt-service/ancs_client.c",
"src/ble/gatt-service/battery_service_client.c",
"src/ble/gatt-service/battery_service_server.c",
"src/ble/gatt-service/cycling_power_service_server.c",
"src/ble/gatt-service/cycling_speed_and_cadence_service_server.c",
"src/ble/gatt-service/device_information_service_client.c",
"src/ble/gatt-service/device_information_service_server.c",
"src/ble/gatt-service/heart_rate_service_server.c",
"src/ble/gatt-service/hids_client.c",
"src/ble/gatt-service/hids_device.c",
"src/ble/gatt-service/nordic_spp_service_server.c",
"src/ble/gatt-service/ublox_spp_service_server.c",
"src/ble/gatt_client.c",
"src/ble/le_device_db_memory.c",
"src/ble/le_device_db_tlv.c",
"src/ble/sm.c",
],
copts = _DISABLE_WARNINGS,
deps = [":pico_btstack_base"],
)
cc_library(
name = "pico_btstack_classic",
srcs = [
"src/classic/a2dp.c",
"src/classic/a2dp_sink.c",
"src/classic/a2dp_source.c",
"src/classic/avdtp.c",
"src/classic/avdtp_acceptor.c",
"src/classic/avdtp_initiator.c",
"src/classic/avdtp_sink.c",
"src/classic/avdtp_source.c",
"src/classic/avdtp_util.c",
"src/classic/avrcp.c",
"src/classic/avrcp_browsing.c",
"src/classic/avrcp_browsing_controller.c",
"src/classic/avrcp_browsing_target.c",
"src/classic/avrcp_controller.c",
"src/classic/avrcp_cover_art_client.c",
"src/classic/avrcp_media_item_iterator.c",
"src/classic/avrcp_target.c",
"src/classic/btstack_cvsd_plc.c",
"src/classic/btstack_link_key_db_tlv.c",
"src/classic/btstack_sbc_plc.c",
"src/classic/device_id_server.c",
"src/classic/gatt_sdp.c",
"src/classic/goep_client.c",
"src/classic/goep_server.c",
"src/classic/hfp.c",
"src/classic/hfp_ag.c",
"src/classic/hfp_gsm_model.c",
"src/classic/hfp_hf.c",
"src/classic/hfp_msbc.c",
"src/classic/hid_device.c",
"src/classic/hid_host.c",
"src/classic/hsp_ag.c",
"src/classic/hsp_hs.c",
"src/classic/obex_iterator.c",
"src/classic/obex_message_builder.c",
"src/classic/obex_parser.c",
"src/classic/pan.c",
"src/classic/pbap_client.c",
"src/classic/rfcomm.c",
"src/classic/sdp_client.c",
"src/classic/sdp_client_rfcomm.c",
"src/classic/sdp_server.c",
"src/classic/sdp_util.c",
"src/classic/spp_server.c",
],
copts = _DISABLE_WARNINGS,
deps = [":pico_btstack_base"],
)
cc_library(
name = "pico_btstack_sbc_encoder",
srcs = [
"3rd-party/bluedroid/encoder/srce/sbc_analysis.c",
"3rd-party/bluedroid/encoder/srce/sbc_dct.c",
"3rd-party/bluedroid/encoder/srce/sbc_dct_coeffs.c",
"3rd-party/bluedroid/encoder/srce/sbc_enc_bit_alloc_mono.c",
"3rd-party/bluedroid/encoder/srce/sbc_enc_bit_alloc_ste.c",
"3rd-party/bluedroid/encoder/srce/sbc_enc_coeffs.c",
"3rd-party/bluedroid/encoder/srce/sbc_encoder.c",
"3rd-party/bluedroid/encoder/srce/sbc_packing.c",
"src/classic/btstack_sbc_encoder_bluedroid.c",
],
copts = _DISABLE_WARNINGS,
includes = ["3rd-party/bluedroid/decoder/include"],
deps = [":pico_btstack_base"],
)
cc_library(
name = "pico_btstack_bnep_lwip",
srcs = [
"platform/lwip/bnep_lwip.c",
"src/classic/bnep.c",
],
copts = _DISABLE_WARNINGS,
includes = ["platform/lwip"],
deps = [":pico_btstack_base"],
)
cc_library(
name = "pico_btstack_bnep_lwip_sys_freertos",
srcs = [
"platform/lwip/bnep_lwip.c",
"src/classic/bnep.c",
],
copts = _DISABLE_WARNINGS,
defines = [
"LWIP_PROVIDE_ERRNO=1",
"PICO_LWIP_CUSTOM_LOCK_TCPIP_CORE=1",
],
includes = [
"platform/freertos",
"platform/lwip",
],
deps = [":pico_btstack_base"],
)

View file

@ -0,0 +1,178 @@
/*
* Copyright (c) 2023 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "pico/btstack_flash_bank.h"
#include "pico/flash.h"
#include "hardware/sync.h"
#include "hardware/flash.h"
#include <string.h>
// Check sizes
static_assert(PICO_FLASH_BANK_TOTAL_SIZE % (FLASH_SECTOR_SIZE * 2) == 0, "PICO_FLASH_BANK_TOTAL_SIZE invalid");
static_assert(PICO_FLASH_BANK_TOTAL_SIZE <= PICO_FLASH_SIZE_BYTES, "PICO_FLASH_BANK_TOTAL_SIZE too big");
// Size of one bank
#define PICO_FLASH_BANK_SIZE (PICO_FLASH_BANK_TOTAL_SIZE / 2)
#if 0
#define DEBUG_PRINT(format,args...) printf(format, ## args)
#else
#define DEBUG_PRINT(...)
#endif
static uint32_t pico_flash_bank_get_size(void * context) {
(void)(context);
return PICO_FLASH_BANK_SIZE;
}
static uint32_t pico_flash_bank_get_alignment(void * context) {
(void)(context);
return 1;
}
typedef struct {
bool op_is_erase;
uintptr_t p0;
uintptr_t p1;
} mutation_operation_t;
static void pico_flash_bank_perform_flash_mutation_operation(void *param) {
const mutation_operation_t *mop = (const mutation_operation_t *)param;
if (mop->op_is_erase) {
flash_range_erase(mop->p0, PICO_FLASH_BANK_SIZE);
} else {
flash_range_program(mop->p0, (const uint8_t *)mop->p1, FLASH_PAGE_SIZE);
}
}
#ifndef pico_flash_bank_get_storage_offset_func
static inline uint32_t pico_flash_bank_get_fixed_storage_offset(void) {
static_assert(PICO_FLASH_BANK_STORAGE_OFFSET + PICO_FLASH_BANK_TOTAL_SIZE <= PICO_FLASH_SIZE_BYTES, "PICO_FLASH_BANK_TOTAL_SIZE too big");
#ifndef NDEBUG
// Check we're not overlapping the binary in flash
extern char __flash_binary_end;
assert(((uintptr_t)&__flash_binary_end - XIP_BASE <= PICO_FLASH_BANK_STORAGE_OFFSET));
#endif
return PICO_FLASH_BANK_STORAGE_OFFSET;
}
#define pico_flash_bank_get_storage_offset_func pico_flash_bank_get_fixed_storage_offset
#else
extern uint32_t pico_flash_bank_get_storage_offset_func(void);
#endif
static void pico_flash_bank_erase(void * context, int bank) {
(void)(context);
DEBUG_PRINT("erase: bank %d\n", bank);
mutation_operation_t mop = {
.op_is_erase = true,
.p0 = pico_flash_bank_get_storage_offset_func() + (PICO_FLASH_BANK_SIZE * bank),
};
// todo choice of timeout and check return code... currently we have no way to return an error
// to the caller anyway. flash_safe_execute asserts by default on problem other than timeout,
// so that's fine for now, and UINT32_MAX is a timeout of 49 days which seems long enough
flash_safe_execute(pico_flash_bank_perform_flash_mutation_operation, &mop, UINT32_MAX);
}
static void pico_flash_bank_read(void *context, int bank, uint32_t offset, uint8_t *buffer, uint32_t size) {
(void)(context);
DEBUG_PRINT("read: bank %d offset %u size %u\n", bank, offset, size);
assert(bank <= 1);
if (bank > 1) return;
assert(offset < PICO_FLASH_BANK_SIZE);
if (offset >= PICO_FLASH_BANK_SIZE) return;
assert((offset + size) <= PICO_FLASH_BANK_SIZE);
if ((offset + size) > PICO_FLASH_BANK_SIZE) return;
// Flash is xip
memcpy(buffer, (void *)(XIP_BASE + pico_flash_bank_get_storage_offset_func() + (PICO_FLASH_BANK_SIZE * bank) + offset), size);
}
static void pico_flash_bank_write(void * context, int bank, uint32_t offset, const uint8_t *data, uint32_t size) {
(void)(context);
DEBUG_PRINT("write: bank %d offset %u size %u\n", bank, offset, size);
assert(bank <= 1);
if (bank > 1) return;
assert(offset < PICO_FLASH_BANK_SIZE);
if (offset >= PICO_FLASH_BANK_SIZE) return;
assert((offset + size) <= PICO_FLASH_BANK_SIZE);
if ((offset + size) > PICO_FLASH_BANK_SIZE) return;
if (size == 0) return;
// calc bank start position
const uint32_t bank_start_pos = pico_flash_bank_get_storage_offset_func() + (PICO_FLASH_BANK_SIZE * bank);
// Calculate first and last page in the bank
const uint32_t first_page = offset / FLASH_PAGE_SIZE;
const uint32_t last_page = (offset + size + FLASH_PAGE_SIZE - 1) / FLASH_PAGE_SIZE;
// Now we only care about the offset in the first page
offset %= FLASH_PAGE_SIZE;
// Amount of data we've copied
uint32_t data_pos = 0;
uint32_t size_left = size;
// Write all the pages required
for(uint32_t page = first_page; page < last_page; page++) {
uint8_t page_data[FLASH_PAGE_SIZE];
assert(data_pos < size && size_left <= size);
// Copy data we're not going to overwrite in the first page
if (page == first_page && offset > 0) {
memcpy(page_data,
(void *)(XIP_BASE + bank_start_pos + (page * FLASH_PAGE_SIZE)),
offset);
}
// Copy the data we're not going to overwrite in the last page
if (page == last_page - 1 && (offset + size_left) < FLASH_PAGE_SIZE) {
memcpy(page_data + offset + size_left,
(void *)(XIP_BASE + bank_start_pos + (page * FLASH_PAGE_SIZE) + offset + size_left),
FLASH_PAGE_SIZE - offset - size_left);
}
// Now copy the new data into the page
const uint32_t size_to_copy = MIN(size_left, FLASH_PAGE_SIZE - offset);
memcpy(page_data + offset, data + data_pos, size_to_copy);
data_pos += size_to_copy;
size_left -= size_to_copy;
// zero offset for the following pages
offset = 0;
// Now program the entire page
mutation_operation_t mop = {
.op_is_erase = false,
.p0 = bank_start_pos + (page * FLASH_PAGE_SIZE),
.p1 = (uintptr_t)page_data
};
// todo choice of timeout and check return code... currently we have no way to return an error
// to the caller anyway. flash_safe_execute asserts by default on problem other than timeout,
// so that's fine for now, and UINT32_MAX is a timeout of 49 days which seems long enough
flash_safe_execute(pico_flash_bank_perform_flash_mutation_operation, &mop, UINT32_MAX);
}
}
static const hal_flash_bank_t pico_flash_bank_instance_obj = {
/* uint32_t (*get_size)(..) */ &pico_flash_bank_get_size,
/* uint32_t (*get_alignment)(..); */ &pico_flash_bank_get_alignment,
/* void (*erase)(..); */ &pico_flash_bank_erase,
/* void (*read)(..); */ &pico_flash_bank_read,
/* void (*write)(..); */ &pico_flash_bank_write,
};
const hal_flash_bank_t *pico_flash_bank_instance(void) {
return &pico_flash_bank_instance_obj;
}

View file

@ -0,0 +1,155 @@
/*
* Copyright (c) 2023 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "pico/btstack_run_loop_async_context.h"
#include "hardware/sync.h"
static async_context_t *btstack_async_context;
static async_at_time_worker_t btstack_timeout_worker;
static async_when_pending_worker_t btstack_processing_worker;
static void btstack_timeout_reached(async_context_t *context, async_at_time_worker_t *worker);
static void btstack_work_pending(async_context_t *context, async_when_pending_worker_t *worker);
static volatile bool run_loop_exit;
static void btstack_run_loop_async_context_init(void) {
btstack_run_loop_base_init();
btstack_timeout_worker.do_work = btstack_timeout_reached;
btstack_processing_worker.do_work = btstack_work_pending;
async_context_add_when_pending_worker(btstack_async_context, &btstack_processing_worker);
}
static void btstack_run_loop_async_context_add_data_source(btstack_data_source_t * data_source) {
async_context_acquire_lock_blocking(btstack_async_context);
btstack_run_loop_base_add_data_source(data_source);
async_context_release_lock(btstack_async_context);
}
static bool btstack_run_loop_async_context_remove_data_source(btstack_data_source_t * data_source) {
async_context_acquire_lock_blocking(btstack_async_context);
bool rc = btstack_run_loop_base_remove_data_source(data_source);
async_context_release_lock(btstack_async_context);
return rc;
}
static void btstack_run_loop_async_context_enable_data_source_callbacks(btstack_data_source_t * data_source, uint16_t callbacks) {
async_context_acquire_lock_blocking(btstack_async_context);
btstack_run_loop_base_enable_data_source_callbacks(data_source, callbacks);
async_context_release_lock(btstack_async_context);
}
static void btstack_run_loop_async_context_disable_data_source_callbacks(btstack_data_source_t * data_source, uint16_t callbacks) {
async_context_acquire_lock_blocking(btstack_async_context);
btstack_run_loop_base_disable_data_source_callbacks(data_source, callbacks);
async_context_release_lock(btstack_async_context);
}
static void btstack_run_loop_async_context_set_timer(btstack_timer_source_t *ts, uint32_t timeout_in_ms){
async_context_acquire_lock_blocking(btstack_async_context);
ts->timeout = to_ms_since_boot(get_absolute_time()) + timeout_in_ms + 1;
async_context_set_work_pending(btstack_async_context, &btstack_processing_worker);
async_context_release_lock(btstack_async_context);
}
static void btstack_run_loop_async_context_add_timer(btstack_timer_source_t *timer) {
async_context_acquire_lock_blocking(btstack_async_context);
btstack_run_loop_base_add_timer(timer);
async_context_set_work_pending(btstack_async_context, &btstack_processing_worker);
async_context_release_lock(btstack_async_context);
}
static bool btstack_run_loop_async_context_remove_timer(btstack_timer_source_t *timer) {
async_context_acquire_lock_blocking(btstack_async_context);
bool rc = btstack_run_loop_base_remove_timer(timer);
async_context_release_lock(btstack_async_context);
return rc;
}
static void btstack_run_loop_async_context_dump_timer(void){
async_context_acquire_lock_blocking(btstack_async_context);
btstack_run_loop_base_dump_timer();
async_context_release_lock(btstack_async_context);
}
static uint32_t btstack_run_loop_async_context_get_time_ms(void)
{
return to_ms_since_boot(get_absolute_time());
}
static void btstack_run_loop_async_context_execute(void)
{
run_loop_exit = false;
while (!run_loop_exit) {
async_context_poll(btstack_async_context);
async_context_wait_for_work_until(btstack_async_context, at_the_end_of_time);
}
}
static void btstack_run_loop_async_context_trigger_exit(void)
{
run_loop_exit = true;
}
static void btstack_run_loop_async_context_execute_on_main_thread(btstack_context_callback_registration_t *callback_registration)
{
async_context_acquire_lock_blocking(btstack_async_context);
btstack_run_loop_base_add_callback(callback_registration);
async_context_set_work_pending(btstack_async_context, &btstack_processing_worker);
async_context_release_lock(btstack_async_context);
}
static void btstack_run_loop_async_context_poll_data_sources_from_irq(void)
{
async_context_set_work_pending(btstack_async_context, &btstack_processing_worker);
}
static const btstack_run_loop_t btstack_run_loop_async_context = {
&btstack_run_loop_async_context_init,
&btstack_run_loop_async_context_add_data_source,
&btstack_run_loop_async_context_remove_data_source,
&btstack_run_loop_async_context_enable_data_source_callbacks,
&btstack_run_loop_async_context_disable_data_source_callbacks,
&btstack_run_loop_async_context_set_timer,
&btstack_run_loop_async_context_add_timer,
&btstack_run_loop_async_context_remove_timer,
&btstack_run_loop_async_context_execute,
&btstack_run_loop_async_context_dump_timer,
&btstack_run_loop_async_context_get_time_ms,
&btstack_run_loop_async_context_poll_data_sources_from_irq,
&btstack_run_loop_async_context_execute_on_main_thread,
&btstack_run_loop_async_context_trigger_exit,
};
const btstack_run_loop_t *btstack_run_loop_async_context_get_instance(async_context_t *async_context)
{
assert(!btstack_async_context || btstack_async_context == async_context);
btstack_async_context = async_context;
return &btstack_run_loop_async_context;
}
static void btstack_timeout_reached(__unused async_context_t *context, __unused async_at_time_worker_t *worker) {
// simply wakeup worker
async_context_set_work_pending(btstack_async_context, &btstack_processing_worker);
}
static void btstack_work_pending(__unused async_context_t *context, __unused async_when_pending_worker_t *worker) {
// poll data sources
btstack_run_loop_base_poll_data_sources();
// execute callbacks
btstack_run_loop_base_execute_callbacks();
uint32_t now = to_ms_since_boot(get_absolute_time());
// process timers
btstack_run_loop_base_process_timers(now);
now = to_ms_since_boot(get_absolute_time());
int ms = btstack_run_loop_base_get_time_until_timeout(now);
if (ms == -1) {
async_context_remove_at_time_worker(btstack_async_context, &btstack_timeout_worker);
} else {
async_context_add_at_time_worker_in_ms(btstack_async_context, &btstack_timeout_worker, ms);
}
}

View file

@ -0,0 +1,60 @@
/*
* Copyright (c) 2023 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "btstack_config.h"
#ifdef HAVE_BTSTACK_STDIN
#include "btstack_stdin.h"
#include "btstack_run_loop.h"
#include "pico/stdio.h"
static btstack_data_source_t stdin_data_source;
static void (*stdin_handler)(char c);
// Data source callback, return any character received
static void btstack_stdin_process(__unused struct btstack_data_source *ds, __unused btstack_data_source_callback_type_t callback_type){
if (stdin_handler) {
while(true) {
int c = getchar_timeout_us(0);
if (c == PICO_ERROR_TIMEOUT) return;
(*stdin_handler)(c);
}
}
}
void on_chars_available_callback(__unused void *param) {
btstack_run_loop_poll_data_sources_from_irq();
}
// Test code calls this if HAVE_BTSTACK_STDIN is defined and it wants key presses
void btstack_stdin_setup(void (*handler)(char c)) {
if (stdin_handler) {
return;
}
// set handler
stdin_handler = handler;
// set up polling data_source
btstack_run_loop_set_data_source_handler(&stdin_data_source, &btstack_stdin_process);
btstack_run_loop_enable_data_source_callbacks(&stdin_data_source, DATA_SOURCE_CALLBACK_POLL);
btstack_run_loop_add_data_source(&stdin_data_source);
stdio_set_chars_available_callback(on_chars_available_callback, NULL);
}
// Deinit everything
void btstack_stdin_reset(void){
if (!stdin_handler) {
return;
}
stdio_set_chars_available_callback(NULL, NULL);
stdin_handler = NULL;
btstack_run_loop_remove_data_source(&stdin_data_source);
}
#endif

View file

@ -0,0 +1,27 @@
/**
* \defgroup pico_btstack pico_btstack
* \brief Integration/wrapper libraries for <a href="https://github.com/bluekitchen/btstack">BTstack</a>
* the documentation for which is <a href="https://bluekitchen-gmbh.com/btstack/">here</a>.
*
* A supplemental license for BTstack (in addition to the stock BTstack licensing terms) is provided <a href="https://github.com/raspberrypi/pico-sdk/blob/master/src/rp2_common/pico_btstack/LICENSE.RP">here</a>.
*
* The \c \b pico_btstack_ble library adds the support needed for Bluetooth Low Energy (BLE). The \c \b pico_btstack_classic library adds the support needed for Bluetooth Classic.
* You can link to either library individually, or to both libraries thus enabling dual-mode support provided by BTstack.
*
* To use BTstack you need to provide a \c btstack_config.h file in your source tree and add its location to your include path.
* The BTstack configuration macros \c ENABLE_CLASSIC and \c ENABLE_BLE are defined for you when you link the \c pico_btstack_classic and \c pico_btstack_ble libraries respectively, so you should not define them yourself.
*
* For more details, see <a href="https://bluekitchen-gmbh.com/btstack/develop/#how_to/">How to configure BTstack</a> and the relevant <a href="https://github.com/raspberrypi/pico-examples#pico-w-bluetooth">pico-examples</a>.
*
* The follow libraries are provided for you to link.
* * \c \b pico_btstack_ble - Adds Bluetooth Low Energy (LE) support.
* * \c \b pico_btstack_classic - Adds Bluetooth Classic support.
* * \c \b pico_btstack_sbc_encoder - Adds Bluetooth Sub Band Coding (SBC) encoder support.
* * \c \b pico_btstack_sbc_decoder - Adds Bluetooth Sub Band Coding (SBC) decoder support.
* * \c \b pico_btstack_bnep_lwip - Adds Bluetooth Network Encapsulation Protocol (BNEP) support using LwIP.
* * \c \b pico_btstack_bnep_lwip_sys_freertos - Adds Bluetooth Network Encapsulation Protocol (BNEP) support using LwIP with FreeRTOS for NO_SYS=0.
*
* \note The CMake function pico_btstack_make_gatt_header can be used to run the BTstack compile_gatt tool to make a GATT header file from a BTstack GATT file.
*
* \sa pico_btstack_cyw43 in pico_cyw43_driver, which adds the cyw43 driver support needed for BTstack including BTstack run loop support.
*/

View file

@ -0,0 +1,39 @@
/*
* Copyright (c) 2023 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _PICO_BTSTACK_FLASH_BANK_H
#define _PICO_BTSTACK_FLASH_BANK_H
#include "pico.h"
#include "hardware/flash.h"
#include "hal_flash_bank.h"
#ifdef __cplusplus
extern "C" {
#endif
// PICO_CONFIG: PICO_FLASH_BANK_TOTAL_SIZE, Total size of the Bluetooth flash storage. Must be an even multiple of FLASH_SECTOR_SIZE, type=int, default=FLASH_SECTOR_SIZE * 2, group=pico_btstack
#ifndef PICO_FLASH_BANK_TOTAL_SIZE
#define PICO_FLASH_BANK_TOTAL_SIZE (FLASH_SECTOR_SIZE * 2u)
#endif
// PICO_CONFIG: PICO_FLASH_BANK_STORAGE_OFFSET, Offset in flash of the Bluetooth flash storage, type=int, default=PICO_FLASH_SIZE_BYTES - PICO_FLASH_BANK_TOTAL_SIZE, group=pico_btstack
#ifndef PICO_FLASH_BANK_STORAGE_OFFSET
#define PICO_FLASH_BANK_STORAGE_OFFSET (PICO_FLASH_SIZE_BYTES - PICO_FLASH_BANK_TOTAL_SIZE)
#endif
/**
* \brief Return the singleton BTstack HAL flash instance, used for non-volatile storage
* \ingroup pico_btstack
*
* \note By default two sectors at the end of flash are used (see \c PICO_FLASH_BANK_STORAGE_OFFSET and \c PICO_FLASH_BANK_TOTAL_SIZE)
*/
const hal_flash_bank_t *pico_flash_bank_instance(void);
#ifdef __cplusplus
}
#endif
#endif

View file

@ -0,0 +1,29 @@
/*
* Copyright (c) 2023 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _PICO_BTSTACK_RUN_LOOP_ASYNC_CONTEXT_H
#define _PICO_BTSTACK_RUN_LOOP_ASYNC_CONTEXT_H
#include "btstack_run_loop.h"
#include "pico/async_context.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* \brief Initialize and return the singleton BTstack run loop instance that integrates with the async_context API
* \ingroup pico_btstack
*
* \param context the async_context instance that provides the abstraction for handling asynchronous work.
* \return the BTstack run loop instance
*/
const btstack_run_loop_t *btstack_run_loop_async_context_get_instance(async_context_t *context);
#ifdef __cplusplus
}
#endif
#endif