feat(core): trezorctl working via BLE

tychovrahe/bluetooth/cleaner_disc2
tychovrahe 1 year ago
parent 25c87fd7a3
commit 8761105264

@ -172,7 +172,6 @@ SOURCE_NRFHAL = [
'embed/sdk/nrf52/components/libraries/bootloader/dfu/nrf_dfu_handling_error.c',
'embed/sdk/nrf52/components/libraries/bootloader/dfu/nrf_dfu_mbr.c',
'embed/sdk/nrf52/components/libraries/bootloader/dfu/nrf_dfu_req_handler.c',
'embed/sdk/nrf52/components/libraries/bootloader/serial_dfu/nrf_dfu_serial_uart.c',
'embed/sdk/nrf52/components/libraries/bootloader/dfu/nrf_dfu_settings.c',
'embed/sdk/nrf52/components/libraries/bootloader/dfu/nrf_dfu_transport.c',
'embed/sdk/nrf52/components/libraries/bootloader/dfu/nrf_dfu_utils.c',
@ -191,6 +190,8 @@ SOURCE_NRFHAL = [
SOURCE_BLE_BOOTLOADER = [
'embed/ble_bootloader/main.c',
'embed/ble_bootloader/dfu_public_key.c',
# originally embed/sdk/nrf52/components/libraries/bootloader/serial_dfu/nrf_dfu_serial_uart.c',
'embed/ble_bootloader/nrf_dfu_serial_uart.c',
]
if DEBUG:

@ -60,7 +60,7 @@ SOURCE_MOD += [
]
CPPPATH_MOD += [
'embed/sdk/nrf52/components/nfc/ndef/generic/message',
'embed/sdk/nrf52/components/nfc/ndef/generic/message',
'embed/sdk/nrf52/components/nfc/t2t_lib',
'embed/sdk/nrf52/components/nfc/t4t_parser/hl_detection_procedure',
'embed/sdk/nrf52/components/ble/ble_services/ble_ancs_c',
@ -77,9 +77,10 @@ CPPPATH_MOD += [
'embed/sdk/nrf52/components/libraries/fstorage',
'embed/sdk/nrf52/components/nfc/ndef/text',
'embed/sdk/nrf52/components/libraries/mutex',
'embed/sdk/nrf52/components/libraries/gpiote',
'embed/sdk/nrf52/components/libraries/gfx',
'embed/sdk/nrf52/components/libraries/bootloader/ble_dfu',
'embed/sdk/nrf52/components/nfc/ndef/connection_handover/common',
'embed/sdk/nrf52/components/libraries/fifo',
'embed/sdk/nrf52/components/boards',
'embed/sdk/nrf52/components/nfc/ndef/generic/record',
'embed/sdk/nrf52/components/nfc/t4t_parser/cc_file',
@ -99,6 +100,7 @@ CPPPATH_MOD += [
'embed/sdk/nrf52/components/ble/common',
'embed/sdk/nrf52/components/ble/ble_services/ble_lls',
'embed/sdk/nrf52/components/nfc/platform',
'embed/sdk/nrf52/components/libraries/bsp',
'embed/sdk/nrf52/components/nfc/ndef/connection_handover/ac_rec',
'embed/sdk/nrf52/components/ble/ble_services/ble_bas',
'embed/sdk/nrf52/components/libraries/mpu',
@ -123,6 +125,7 @@ CPPPATH_MOD += [
'embed/sdk/nrf52/components/libraries/cli',
'embed/sdk/nrf52/components/ble/ble_services/ble_lbs',
'embed/sdk/nrf52/components/ble/ble_services/ble_hts',
'embed/sdk/nrf52/components/ble/ble_services/ble_cts_c',
'embed/sdk/nrf52/components/libraries/crc16',
'embed/sdk/nrf52/components/nfc/t4t_parser/apdu',
'embed/sdk/nrf52/components/libraries/util',
@ -132,7 +135,9 @@ CPPPATH_MOD += [
'embed/sdk/nrf52/components/libraries/ecc',
'embed/sdk/nrf52/components/libraries/hardfault',
'embed/sdk/nrf52/components/ble/ble_services/ble_cscs',
'embed/sdk/nrf52/components/libraries/uart',
'embed/sdk/nrf52/components/libraries/hci',
'embed/sdk/nrf52/components/libraries/usbd/class/hid/kbd',
'embed/sdk/nrf52/components/libraries/timer',
'embed/sdk/nrf52/components/softdevice/s140/headers',
'embed/sdk/nrf52/integration/nrfx',
@ -144,7 +149,7 @@ CPPPATH_MOD += [
'embed/sdk/nrf52/components/libraries/sdcard',
'embed/sdk/nrf52/components/nfc/ndef/parser/record',
'embed/sdk/nrf52/modules/nrfx/mdk',
'embed/sdk/nrf52/components/ble/ble_services/ble_cts_c',
'embed/sdk/nrf52/components/ble/ble_link_ctx_manager',
'embed/sdk/nrf52/components/ble/ble_services/ble_nus',
'embed/sdk/nrf52/components/libraries/twi_mngr',
'embed/sdk/nrf52/components/ble/ble_services/ble_hids',
@ -164,12 +169,12 @@ CPPPATH_MOD += [
'embed/sdk/nrf52/components/nfc/ndef/uri',
'embed/sdk/nrf52/components/ble/nrf_ble_gatt',
'embed/sdk/nrf52/components/ble/nrf_ble_qwr',
'embed/sdk/nrf52/components/libraries/gfx',
'embed/sdk/nrf52/components/libraries/gpiote',
'embed/sdk/nrf52/components/libraries/button',
'embed/sdk/nrf52/modules/nrfx',
'embed/sdk/nrf52/components/libraries/twi_sensor',
'embed/sdk/nrf52/integration/nrfx/legacy',
'embed/sdk/nrf52/components/libraries/usbd/class/hid/kbd',
'embed/sdk/nrf52/components/libraries/usbd',
'embed/sdk/nrf52/components/nfc/ndef/connection_handover/ep_oob_rec',
'embed/sdk/nrf52/external/segger_rtt',
'embed/sdk/nrf52/components/libraries/atomic_fifo',
@ -183,7 +188,6 @@ CPPPATH_MOD += [
'embed/sdk/nrf52/components/ble/ble_services/ble_hrs',
'embed/sdk/nrf52/components/ble/ble_services/ble_rscs',
'embed/sdk/nrf52/components/nfc/ndef/connection_handover/hs_rec',
'embed/sdk/nrf52/components/libraries/usbd',
'embed/sdk/nrf52/components/nfc/ndef/conn_hand_parser/ac_rec_parser',
'embed/sdk/nrf52/components/libraries/stack_guard',
'embed/sdk/nrf52/components/libraries/log/src',
@ -205,8 +209,10 @@ SOURCE_NRFHAL = [
'embed/sdk/nrf52/components/libraries/util/app_error.c',
'embed/sdk/nrf52/components/libraries/util/app_error_handler_gcc.c',
'embed/sdk/nrf52/components/libraries/util/app_error_weak.c',
'embed/sdk/nrf52/components/libraries/fifo/app_fifo.c',
'embed/sdk/nrf52/components/libraries/scheduler/app_scheduler.c',
'embed/sdk/nrf52/components/libraries/timer/app_timer2.c',
'embed/sdk/nrf52/components/libraries/uart/app_uart_fifo.c',
'embed/sdk/nrf52/components/libraries/util/app_util_platform.c',
'embed/sdk/nrf52/components/libraries/timer/drv_rtc.c',
'embed/sdk/nrf52/components/libraries/hardfault/hardfault_implementation.c',
@ -223,6 +229,7 @@ SOURCE_NRFHAL = [
'embed/sdk/nrf52/components/libraries/experimental_section_vars/nrf_section_iter.c',
'embed/sdk/nrf52/components/libraries/sortlist/nrf_sortlist.c',
'embed/sdk/nrf52/components/libraries/strerror/nrf_strerror.c',
'embed/sdk/nrf52/components/libraries/uart/retarget.c',
'embed/sdk/nrf52/modules/nrfx/mdk/system_nrf52840.c',
'embed/sdk/nrf52/components/boards/boards.c',
'embed/sdk/nrf52/integration/nrfx/legacy/nrf_drv_clock.c',
@ -233,14 +240,18 @@ SOURCE_NRFHAL = [
'embed/sdk/nrf52/modules/nrfx/drivers/src/prs/nrfx_prs.c',
'embed/sdk/nrf52/modules/nrfx/drivers/src/nrfx_uart.c',
'embed/sdk/nrf52/modules/nrfx/drivers/src/nrfx_uarte.c',
'embed/sdk/nrf52/components/libraries/bsp/bsp.c',
'embed/sdk/nrf52/components/libraries/bsp/bsp_btn_ble.c',
'embed/sdk/nrf52/components/ble/common/ble_advdata.c',
'embed/sdk/nrf52/components/ble/ble_advertising/ble_advertising.c',
'embed/sdk/nrf52/components/ble/common/ble_conn_params.c',
'embed/sdk/nrf52/components/ble/common/ble_conn_state.c',
'embed/sdk/nrf52/components/ble/ble_link_ctx_manager/ble_link_ctx_manager.c',
'embed/sdk/nrf52/components/ble/common/ble_srv_common.c',
'embed/sdk/nrf52/components/ble/nrf_ble_gatt/nrf_ble_gatt.c',
'embed/sdk/nrf52/components/ble/nrf_ble_qwr/nrf_ble_qwr.c',
'embed/sdk/nrf52/external/utf_converter/utf.c',
'embed/sdk/nrf52/components/ble/ble_services/ble_lbs/ble_lbs.c',
'embed/sdk/nrf52/components/ble/ble_services/ble_nus/ble_nus.c',
'embed/sdk/nrf52/components/softdevice/common/nrf_sdh.c',
'embed/sdk/nrf52/components/softdevice/common/nrf_sdh_ble.c',
'embed/sdk/nrf52/components/softdevice/common/nrf_sdh_soc.c',

@ -382,8 +382,9 @@ SOURCE_TREZORHAL = [
'embed/trezorhal/usbd_ioreq.c',
'embed/trezorhal/util.s',
'embed/trezorhal/vectortable.s',
'embed/trezorhal/dfu/dfu.c',
'embed/trezorhal/dfu/fwu.c',
'embed/trezorhal/ble/comm.c',
'embed/trezorhal/ble/dfu.c',
'embed/trezorhal/ble/fwu.c',
]
@ -481,7 +482,7 @@ env.Replace(
'embed/rust',
'embed/firmware',
'embed/lib',
'embed/firmware/dfu',
'embed/firmware/ble',
'embed/trezorhal',
'embed/extmod/modtrezorui',
'vendor/micropython',

@ -338,7 +338,8 @@ SOURCE_MICROPYTHON = [
SOURCE_UNIX = [
'embed/unix/common.c',
'embed/unix/dfu/dfu.c',
'embed/unix/ble/comm.c',
'embed/unix/ble/dfu.c',
'embed/unix/display-unix.c',
'embed/unix/flash.c',
'embed/unix/main.c',
@ -445,6 +446,7 @@ env.Replace(
'embed/rust',
'embed/lib',
'embed/unix',
'embed/unix/ble',
'embed/extmod/modtrezorui',
'vendor/micropython',
'vendor/micropython/ports/unix',

@ -77,7 +77,7 @@ static void on_error(void) {
void app_error_handler(uint32_t error_code, uint32_t line_num,
const uint8_t* p_file_name) {
NRF_LOG_ERROR("%s:%d", p_file_name, line_num);
NRF_LOG_ERROR("%s:%d, %d", p_file_name, line_num, error_code);
on_error();
}

@ -0,0 +1,273 @@
// clang-format off
/**
* Copyright (c) 2016 - 2021, Nordic Semiconductor ASA
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice, this
* list of conditions and the following disclaimer.
*
* 2. Redistributions in binary form, except as embedded into a Nordic
* Semiconductor ASA integrated circuit in a product or a software update for
* such product, must reproduce the above copyright notice, this list of
* conditions and the following disclaimer in the documentation and/or other
* materials provided with the distribution.
*
* 3. Neither the name of Nordic Semiconductor ASA nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* 4. This software, with or without modification, must only be used with a
* Nordic Semiconductor ASA integrated circuit.
*
* 5. Any software provided in binary form under this license must not be reverse
* engineered, decompiled, modified and/or disassembled.
*
* THIS SOFTWARE IS PROVIDED BY NORDIC SEMICONDUCTOR ASA "AS IS" AND ANY EXPRESS
* OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA OR CONTRIBUTORS 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 THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#include "nrf_dfu_serial.h"
#include <string.h>
#include "boards.h"
#include "app_util_platform.h"
#include "nrf_dfu_transport.h"
#include "nrf_dfu_req_handler.h"
#include "slip.h"
#include "nrf_balloc.h"
#include "nrf_drv_uart.h"
#define NRF_LOG_MODULE_NAME nrf_dfu_serial_uart
#include "nrf_log.h"
NRF_LOG_MODULE_REGISTER();
/**@file
*
* @defgroup nrf_dfu_serial_uart DFU Serial UART transport
* @ingroup nrf_dfu
* @brief Device Firmware Update (DFU) transport layer using UART.
*/
#define NRF_SERIAL_OPCODE_SIZE (sizeof(uint8_t))
#define NRF_UART_MAX_RESPONSE_SIZE_SLIP (2 * NRF_SERIAL_MAX_RESPONSE_SIZE + 1)
#define RX_BUF_SIZE (64) //to get 64bytes payload
#define OPCODE_OFFSET (sizeof(uint32_t) - NRF_SERIAL_OPCODE_SIZE)
#define DATA_OFFSET (OPCODE_OFFSET + NRF_SERIAL_OPCODE_SIZE)
#define UART_SLIP_MTU (2 * (RX_BUF_SIZE + 1) + 1)
#define BALLOC_BUF_SIZE ((CEIL_DIV((RX_BUF_SIZE+OPCODE_SIZE),sizeof(uint32_t))*sizeof(uint32_t)))
NRF_BALLOC_DEF(m_payload_pool, (UART_SLIP_MTU + 1), NRF_DFU_SERIAL_UART_RX_BUFFERS);
static nrf_drv_uart_t m_uart = NRF_DRV_UART_INSTANCE(0);
static uint8_t m_rx_byte;
static nrf_dfu_serial_t m_serial;
static slip_t m_slip;
static uint8_t m_rsp_buf[NRF_UART_MAX_RESPONSE_SIZE_SLIP];
static bool m_active;
static bool m_waiting_for_buffers = false;
static nrf_dfu_observer_t m_observer;
static uint32_t uart_dfu_transport_init(nrf_dfu_observer_t observer);
static uint32_t uart_dfu_transport_close(nrf_dfu_transport_t const * p_exception);
DFU_TRANSPORT_REGISTER(nrf_dfu_transport_t const uart_dfu_transport) =
{
.init_func = uart_dfu_transport_init,
.close_func = uart_dfu_transport_close,
};
static void payload_free(void * p_buf)
{
uint8_t * p_buf_root = (uint8_t *)p_buf - DATA_OFFSET; //pointer is shifted to point to data
nrf_balloc_free(&m_payload_pool, p_buf_root);
uint8_t utilization = m_payload_pool.p_stack_limit - m_payload_pool.p_cb->p_stack_pointer;
if (m_waiting_for_buffers && utilization < NRF_DFU_SERIAL_UART_RX_BUFFERS - 2) {
NRF_LOG_INFO("Buffer utilization: %d, resuming.", utilization);
nrf_gpio_pin_set(RTS_PIN_NUMBER);
nrf_gpio_cfg_output(RTS_PIN_NUMBER);
m_uart.uarte.p_reg->PSEL.RTS = RTS_PIN_NUMBER;
m_waiting_for_buffers = false;
}
}
static ret_code_t rsp_send(uint8_t const * p_data, uint32_t length)
{
uint32_t slip_len;
(void) slip_encode(m_rsp_buf, (uint8_t *)p_data, length, &slip_len);
return nrf_drv_uart_tx(&m_uart, m_rsp_buf, slip_len);
}
static __INLINE void on_rx_complete(nrf_dfu_serial_t * p_transport, uint8_t * p_data, uint8_t len)
{
ret_code_t ret_code = NRF_ERROR_TIMEOUT;
// Check if there is byte to process. Zero length transfer means that RXTO occured.
if (len)
{
ret_code = slip_decode_add_byte(&m_slip, p_data[0]);
}
(void) nrf_drv_uart_rx(&m_uart, &m_rx_byte, 1);
if (ret_code == NRF_SUCCESS)
{
nrf_dfu_serial_on_packet_received(p_transport,
(uint8_t const *)m_slip.p_buffer,
m_slip.current_index);
uint8_t * p_rx_buf = nrf_balloc_alloc(&m_payload_pool);
uint8_t utilization = m_payload_pool.p_stack_limit - m_payload_pool.p_cb->p_stack_pointer;
if (!m_waiting_for_buffers && utilization >= NRF_DFU_SERIAL_UART_RX_BUFFERS - 2) {
NRF_LOG_INFO("Buffer utilization: %d, waiting.", utilization);
m_uart.uarte.p_reg->PSEL.RTS = NRF_UART_PSEL_DISCONNECTED;
nrf_gpio_cfg_output(RTS_PIN_NUMBER);
nrf_gpio_pin_set(RTS_PIN_NUMBER);
m_waiting_for_buffers = true;
}
if (p_rx_buf == NULL)
{
NRF_LOG_ERROR("Failed to allocate buffer");
return;
}
NRF_LOG_INFO("Allocated buffer %x", p_rx_buf);
// reset the slip decoding
m_slip.p_buffer = &p_rx_buf[OPCODE_OFFSET];
m_slip.current_index = 0;
m_slip.state = SLIP_STATE_DECODING;
}
}
static void uart_event_handler(nrf_drv_uart_event_t * p_event, void * p_context)
{
switch (p_event->type)
{
case NRF_DRV_UART_EVT_RX_DONE:
on_rx_complete((nrf_dfu_serial_t*)p_context,
p_event->data.rxtx.p_data,
p_event->data.rxtx.bytes);
break;
case NRF_DRV_UART_EVT_ERROR:
APP_ERROR_HANDLER(p_event->data.error.error_mask);
break;
default:
// No action.
break;
}
}
static uint32_t uart_dfu_transport_init(nrf_dfu_observer_t observer)
{
uint32_t err_code = NRF_SUCCESS;
if (m_active)
{
return err_code;
}
NRF_LOG_DEBUG("serial_dfu_transport_init()");
m_observer = observer;
err_code = nrf_balloc_init(&m_payload_pool);
if (err_code != NRF_SUCCESS)
{
return err_code;
}
uint8_t * p_rx_buf = nrf_balloc_alloc(&m_payload_pool);
m_slip.p_buffer = &p_rx_buf[OPCODE_OFFSET];
m_slip.current_index = 0;
m_slip.buffer_len = UART_SLIP_MTU;
m_slip.state = SLIP_STATE_DECODING;
m_serial.rsp_func = rsp_send;
m_serial.payload_free_func = payload_free;
m_serial.mtu = UART_SLIP_MTU;
m_serial.p_rsp_buf = &m_rsp_buf[NRF_UART_MAX_RESPONSE_SIZE_SLIP -
NRF_SERIAL_MAX_RESPONSE_SIZE];
m_serial.p_low_level_transport = &uart_dfu_transport;
nrf_drv_uart_config_t uart_config = NRF_DRV_UART_DEFAULT_CONFIG;
uart_config.pseltxd = TX_PIN_NUMBER;
uart_config.pselrxd = RX_PIN_NUMBER;
uart_config.pselcts = CTS_PIN_NUMBER;
uart_config.pselrts = RTS_PIN_NUMBER;
uart_config.hwfc = NRF_UART_HWFC_ENABLED;
uart_config.p_context = &m_serial;
nrf_gpio_cfg(
RTS_PIN_NUMBER,
NRF_GPIO_PIN_DIR_OUTPUT,
NRF_GPIO_PIN_INPUT_DISCONNECT,
NRF_GPIO_PIN_NOPULL,
NRF_GPIO_PIN_S0S1,
NRF_GPIO_PIN_NOSENSE);
nrf_gpio_pin_write(RTS_PIN_NUMBER, 0);
err_code = nrf_drv_uart_init(&m_uart, &uart_config, uart_event_handler);
if (err_code != NRF_SUCCESS)
{
NRF_LOG_ERROR("Failed initializing uart");
return err_code;
}
err_code = nrf_drv_uart_rx(&m_uart, &m_rx_byte, 1);
if (err_code != NRF_SUCCESS)
{
NRF_LOG_ERROR("Failed initializing rx");
}
NRF_LOG_DEBUG("serial_dfu_transport_init() completed");
m_active = true;
if (m_observer)
{
m_observer(NRF_DFU_EVT_TRANSPORT_ACTIVATED);
}
return err_code;
}
static uint32_t uart_dfu_transport_close(nrf_dfu_transport_t const * p_exception)
{
if ((m_active == true) && (p_exception != &uart_dfu_transport))
{
nrf_drv_uart_uninit(&m_uart);
m_active = false;
}
return NRF_SUCCESS;
}

@ -1365,7 +1365,7 @@
// <i> to received packets being dropped.
#ifndef NRF_DFU_SERIAL_UART_RX_BUFFERS
#define NRF_DFU_SERIAL_UART_RX_BUFFERS 3
#define NRF_DFU_SERIAL_UART_RX_BUFFERS 10
#endif
// </h>
@ -1760,7 +1760,7 @@
// <268435456=> 1000000 baud
#ifndef UART_DEFAULT_CONFIG_BAUDRATE
#define UART_DEFAULT_CONFIG_BAUDRATE 30801920
#define UART_DEFAULT_CONFIG_BAUDRATE 268435456
#endif
// <o> UART_DEFAULT_CONFIG_IRQ_PRIORITY - Interrupt priority

@ -1,5 +1,5 @@
/**
* Copyright (c) 2015 - 2021, Nordic Semiconductor ASA
* Copyright (c) 2014 - 2021, Nordic Semiconductor ASA
*
* All rights reserved.
*
@ -38,26 +38,29 @@
* POSSIBILITY OF SUCH DAMAGE.
*
*/
/**
* @brief Blinky Sample Application main file.
/** @file
*
* @defgroup ble_sdk_uart_over_ble_main main.c
* @{
* @ingroup ble_sdk_app_nus_eval
* @brief UART over BLE application main file.
*
* This file contains the source code for a sample server application using the
* LED Button service.
* This file contains the source code for a sample application that uses the
* Nordic UART service. This application uses the @ref srvlib_conn_params
* module.
*/
#include <stdint.h>
#include <string.h>
#include "app_button.h"
#include "app_error.h"
#include "app_timer.h"
#include "ble.h"
#include "app_uart.h"
#include "app_util_platform.h"
#include "ble_advdata.h"
#include "ble_advertising.h"
#include "ble_conn_params.h"
#include "ble_err.h"
#include "ble_hci.h"
#include "ble_lbs.h"
#include "ble_srv_common.h"
#include "boards.h"
#include "ble_nus.h"
#include "bsp_btn_ble.h"
#include "nordic_common.h"
#include "nrf.h"
#include "nrf_ble_gatt.h"
@ -65,103 +68,95 @@
#include "nrf_pwr_mgmt.h"
#include "nrf_sdh.h"
#include "nrf_sdh_ble.h"
#include "nrf_sdh_soc.h"
#if defined(UART_PRESENT)
#include "nrf_uart.h"
#endif
#if defined(UARTE_PRESENT)
#include "nrf_uarte.h"
#endif
#include "nrf_log.h"
#include "nrf_log_ctrl.h"
#include "nrf_log_default_backends.h"
#define ADVERTISING_LED \
BSP_BOARD_LED_0 /**< Is on when device is advertising. */
#define CONNECTED_LED BSP_BOARD_LED_1 /**< Is on when device has connected. */
#define LEDBUTTON_LED \
BSP_BOARD_LED_2 /**< LED to be toggled with the help of the LED Button \
Service. */
#define LEDBUTTON_BUTTON \
BSP_BUTTON_0 /**< Button that will trigger the notification event with the \
LED Button Service */
#define APP_BLE_CONN_CFG_TAG \
1 /**< A tag identifying the SoftDevice BLE configuration. */
#define DEVICE_NAME \
"Nordic_Blinky" /**< Name of device. Will be included in the advertising \
data. */
#define DEVICE_NAME \
"Trezor" /**< Name of device. Will be included in the advertising data. \
*/
#define NUS_SERVICE_UUID_TYPE \
BLE_UUID_TYPE_VENDOR_BEGIN /**< UUID type for the Nordic UART Service \
(vendor specific). */
#define APP_BLE_OBSERVER_PRIO \
3 /**< Application's BLE observer priority. You shouldn't need to modify \
this value. */
#define APP_BLE_CONN_CFG_TAG \
1 /**< A tag identifying the SoftDevice BLE configuration. */
#define APP_ADV_INTERVAL \
64 /**< The advertising interval (in units of 0.625 ms; this value \
64 /**< The advertising interval (in units of 0.625 ms. This value \
corresponds to 40 ms). */
#define APP_ADV_DURATION \
BLE_GAP_ADV_TIMEOUT_GENERAL_UNLIMITED /**< The advertising time-out (in \
units of seconds). When set to 0, \
we will never time out. */
#define MIN_CONN_INTERVAL \
MSEC_TO_UNITS(100, UNIT_1_25_MS) /**< Minimum acceptable connection interval \
(0.5 seconds). */
#define MAX_CONN_INTERVAL \
MSEC_TO_UNITS( \
200, \
UNIT_1_25_MS) /**< Maximum acceptable connection interval (1 second). */
#define APP_ADV_DURATION \
18000 /**< The advertising duration (180 seconds) in units of 10 \
milliseconds. */
#define MIN_CONN_INTERVAL \
MSEC_TO_UNITS( \
20, UNIT_1_25_MS) /**< Minimum acceptable connection interval (20 ms), \
Connection interval uses 1.25 ms units. */
#define MAX_CONN_INTERVAL \
MSEC_TO_UNITS( \
75, UNIT_1_25_MS) /**< Maximum acceptable connection interval (75 ms), \
Connection interval uses 1.25 ms units. */
#define SLAVE_LATENCY 0 /**< Slave latency. */
#define CONN_SUP_TIMEOUT \
MSEC_TO_UNITS( \
4000, UNIT_10_MS) /**< Connection supervisory time-out (4 seconds). */
#define FIRST_CONN_PARAMS_UPDATE_DELAY \
APP_TIMER_TICKS( \
20000) /**< Time from initiating event (connect or start of \
notification) to first time sd_ble_gap_conn_param_update is \
called (15 seconds). */
#define NEXT_CONN_PARAMS_UPDATE_DELAY \
APP_TIMER_TICKS( \
5000) /**< Time between each call to sd_ble_gap_conn_param_update after \
the first call (5 seconds). */
#define CONN_SUP_TIMEOUT \
MSEC_TO_UNITS(4000, \
UNIT_10_MS) /**< Connection supervisory timeout (4 seconds), \
Supervision Timeout uses 10 ms units. */
#define FIRST_CONN_PARAMS_UPDATE_DELAY \
APP_TIMER_TICKS( \
5000) /**< Time from initiating event (connect or start of notification) \
to first time sd_ble_gap_conn_param_update is called (5 \
seconds). */
#define NEXT_CONN_PARAMS_UPDATE_DELAY \
APP_TIMER_TICKS( \
30000) /**< Time between each call to sd_ble_gap_conn_param_update after \
the first call (30 seconds). */
#define MAX_CONN_PARAMS_UPDATE_COUNT \
3 /**< Number of attempts before giving up the connection parameter \
negotiation. */
#define BUTTON_DETECTION_DELAY \
APP_TIMER_TICKS(50) /**< Delay from a GPIOTE event until a button is \
reported as pushed (in number of timer ticks). */
#define DEAD_BEEF \
0xDEADBEEF /**< Value used as error code on stack dump, can be used to \
identify stack location on stack unwind. */
BLE_LBS_DEF(m_lbs); /**< LED Button Service instance. */
NRF_BLE_GATT_DEF(m_gatt); /**< GATT module instance. */
NRF_BLE_QWR_DEF(m_qwr); /**< Context for the Queued Write module.*/
#define UART_TX_BUF_SIZE 256 /**< UART TX buffer size. */
#define UART_RX_BUF_SIZE 256 /**< UART RX buffer size. */
BLE_NUS_DEF(m_nus,
NRF_SDH_BLE_TOTAL_LINK_COUNT); /**< BLE NUS service instance. */
NRF_BLE_GATT_DEF(m_gatt); /**< GATT module instance. */
NRF_BLE_QWR_DEF(m_qwr); /**< Context for the Queued Write module.*/
BLE_ADVERTISING_DEF(m_advertising); /**< Advertising module instance. */
static uint16_t m_conn_handle =
BLE_CONN_HANDLE_INVALID; /**< Handle of the current connection. */
static uint8_t m_adv_handle =
BLE_GAP_ADV_SET_HANDLE_NOT_SET; /**< Advertising handle used to identify an
advertising set. */
static uint8_t
m_enc_advdata[BLE_GAP_ADV_SET_DATA_SIZE_MAX]; /**< Buffer for storing an
encoded advertising set. */
static uint8_t m_enc_scan_response_data
[BLE_GAP_ADV_SET_DATA_SIZE_MAX]; /**< Buffer for storing an encoded scan
data. */
/**@brief Struct that contains pointers to the encoded advertising data. */
static ble_gap_adv_data_t m_adv_data = {
.adv_data = {.p_data = m_enc_advdata, .len = BLE_GAP_ADV_SET_DATA_SIZE_MAX},
.scan_rsp_data = {
.p_data = m_enc_scan_response_data, .len = BLE_GAP_ADV_SET_DATA_SIZE_MAX
}};
static uint16_t m_ble_nus_max_data_len =
BLE_GATT_ATT_MTU_DEFAULT -
3; /**< Maximum length of data (in bytes) that can be transmitted to the
peer by the Nordic UART service module. */
static ble_uuid_t m_adv_uuids[] = /**< Universally unique service identifier. */
{{BLE_UUID_NUS_SERVICE, NUS_SERVICE_UUID_TYPE}};
/**@brief Function for assert macro callback.
*
* @details This function will be called in case of an assert in the SoftDevice.
*
* @warning This handler is an example only and does not fit a final product.
* You need to analyze how your product is supposed to react in case of Assert.
* You need to analyse how your product is supposed to react in case of Assert.
* @warning On assert from the SoftDevice, the system can only recover on reset.
*
* @param[in] line_num Line number of the failing ASSERT call.
@ -171,30 +166,21 @@ void assert_nrf_callback(uint16_t line_num, const uint8_t *p_file_name) {
app_error_handler(DEAD_BEEF, line_num, p_file_name);
}
/**@brief Function for the LEDs initialization.
*
* @details Initializes all LEDs used by the application.
*/
static void leds_init(void) { bsp_board_init(BSP_INIT_LEDS); }
/**@brief Function for the Timer initialization.
*
* @details Initializes the timer module.
/**@brief Function for initializing the timer module.
*/
static void timers_init(void) {
// Initialize timer module, making it use the scheduler
ret_code_t err_code = app_timer_init();
APP_ERROR_CHECK(err_code);
}
/**@brief Function for the GAP initialization.
*
* @details This function sets up all the necessary GAP (Generic Access Profile)
* parameters of the device including the device name, appearance, and the
* preferred connection parameters.
* @details This function will set up all the necessary GAP (Generic Access
* Profile) parameters of the device. It also sets the permissions and
* appearance.
*/
static void gap_params_init(void) {
ret_code_t err_code;
uint32_t err_code;
ble_gap_conn_params_t gap_conn_params;
ble_gap_conn_sec_mode_t sec_mode;
@ -215,63 +201,6 @@ static void gap_params_init(void) {
APP_ERROR_CHECK(err_code);
}
/**@brief Function for initializing the GATT module.
*/
static void gatt_init(void) {
ret_code_t err_code = nrf_ble_gatt_init(&m_gatt, NULL);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for initializing the Advertising functionality.
*
* @details Encodes the required advertising data and passes it to the stack.
* Also builds a structure to be passed to the stack when starting
* advertising.
*/
static void advertising_init(void) {
ret_code_t err_code;
ble_advdata_t advdata;
ble_advdata_t srdata;
ble_uuid_t adv_uuids[] = {{LBS_UUID_SERVICE, m_lbs.uuid_type}};
// Build and set advertising data.
memset(&advdata, 0, sizeof(advdata));
advdata.name_type = BLE_ADVDATA_FULL_NAME;
advdata.include_appearance = true;
advdata.flags = BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE;
memset(&srdata, 0, sizeof(srdata));
srdata.uuids_complete.uuid_cnt = sizeof(adv_uuids) / sizeof(adv_uuids[0]);
srdata.uuids_complete.p_uuids = adv_uuids;
err_code = ble_advdata_encode(&advdata, m_adv_data.adv_data.p_data,
&m_adv_data.adv_data.len);
APP_ERROR_CHECK(err_code);
err_code = ble_advdata_encode(&srdata, m_adv_data.scan_rsp_data.p_data,
&m_adv_data.scan_rsp_data.len);
APP_ERROR_CHECK(err_code);
ble_gap_adv_params_t adv_params;
// Set advertising parameters.
memset(&adv_params, 0, sizeof(adv_params));
adv_params.primary_phy = BLE_GAP_PHY_1MBPS;
adv_params.duration = APP_ADV_DURATION;
adv_params.properties.type =
BLE_GAP_ADV_TYPE_CONNECTABLE_SCANNABLE_UNDIRECTED;
adv_params.p_peer_addr = NULL;
adv_params.filter_policy = BLE_GAP_ADV_FP_ANY;
adv_params.interval = APP_ADV_INTERVAL;
err_code =
sd_ble_gap_adv_set_configure(&m_adv_handle, &m_adv_data, &adv_params);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for handling Queued Write Module errors.
*
* @details A pointer to this function will be passed to each service which may
@ -284,29 +213,46 @@ static void nrf_qwr_error_handler(uint32_t nrf_error) {
APP_ERROR_HANDLER(nrf_error);
}
/**@brief Function for handling write events to the LED characteristic.
/**@brief Function for handling the data from the Nordic UART Service.
*
* @details This function will process the data received from the Nordic UART
* BLE Service and send it to the UART module.
*
* @param[in] p_lbs Instance of LED Button Service to which the write
* applies.
* @param[in] led_state Written/desired state of the LED.
* @param[in] p_evt Nordic UART Service event.
*/
static void led_write_handler(uint16_t conn_handle, ble_lbs_t *p_lbs,
uint8_t led_state) {
if (led_state) {
bsp_board_led_on(LEDBUTTON_LED);
NRF_LOG_INFO("Received LED ON!");
} else {
bsp_board_led_off(LEDBUTTON_LED);
NRF_LOG_INFO("Received LED OFF!");
/**@snippet [Handling the data received over BLE] */
static void nus_data_handler(ble_nus_evt_t *p_evt) {
if (p_evt->type == BLE_NUS_EVT_RX_DATA) {
uint32_t err_code;
NRF_LOG_DEBUG("Received data from BLE NUS. Writing data on UART.");
NRF_LOG_HEXDUMP_DEBUG(p_evt->params.rx_data.p_data,
p_evt->params.rx_data.length);
for (uint32_t i = 0; i < p_evt->params.rx_data.length; i++) {
do {
err_code = app_uart_put(p_evt->params.rx_data.p_data[i]);
if ((err_code != NRF_SUCCESS) && (err_code != NRF_ERROR_BUSY)) {
NRF_LOG_ERROR("Failed receiving NUS message. Error 0x%x. ", err_code);
APP_ERROR_CHECK(err_code);
}
} while (err_code == NRF_ERROR_BUSY);
}
// if (p_evt->params.rx_data.p_data[p_evt->params.rx_data.length - 1] ==
// '\r') {
// while (app_uart_put('\n') == NRF_ERROR_BUSY)
// ;
// }
}
}
/**@snippet [Handling the data received over BLE] */
/**@brief Function for initializing services that will be used by the
* application.
*/
static void services_init(void) {
ret_code_t err_code;
ble_lbs_init_t init = {0};
uint32_t err_code;
ble_nus_init_t nus_init;
nrf_ble_qwr_init_t qwr_init = {0};
// Initialize Queued Write Module.
@ -315,17 +261,19 @@ static void services_init(void) {
err_code = nrf_ble_qwr_init(&m_qwr, &qwr_init);
APP_ERROR_CHECK(err_code);
// Initialize LBS.
init.led_write_handler = led_write_handler;
// Initialize NUS.
memset(&nus_init, 0, sizeof(nus_init));
nus_init.data_handler = nus_data_handler;
err_code = ble_lbs_init(&m_lbs, &init);
err_code = ble_nus_init(&m_nus, &nus_init);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for handling the Connection Parameters Module.
/**@brief Function for handling an event from the Connection Parameters Module.
*
* @details This function will be called for all events in the Connection
* Parameters Module that are passed to the application.
* Parameters Module which are passed to the application.
*
* @note All this function does is to disconnect. This could have been done by
* simply setting the disconnect_on_fail config parameter, but instead we use
@ -334,7 +282,7 @@ static void services_init(void) {
* @param[in] p_evt Event received from the Connection Parameters Module.
*/
static void on_conn_params_evt(ble_conn_params_evt_t *p_evt) {
ret_code_t err_code;
uint32_t err_code;
if (p_evt->evt_type == BLE_CONN_PARAMS_EVT_FAILED) {
err_code = sd_ble_gap_disconnect(m_conn_handle,
@ -343,7 +291,7 @@ static void on_conn_params_evt(ble_conn_params_evt_t *p_evt) {
}
}
/**@brief Function for handling a Connection Parameters error.
/**@brief Function for handling errors from the Connection Parameters module.
*
* @param[in] nrf_error Error code containing information about what went
* wrong.
@ -355,7 +303,7 @@ static void conn_params_error_handler(uint32_t nrf_error) {
/**@brief Function for initializing the Connection Parameters module.
*/
static void conn_params_init(void) {
ret_code_t err_code;
uint32_t err_code;
ble_conn_params_init_t cp_init;
memset(&cp_init, 0, sizeof(cp_init));
@ -373,15 +321,45 @@ static void conn_params_init(void) {
APP_ERROR_CHECK(err_code);
}
/**@brief Function for starting advertising.
/**@brief Function for putting the chip into sleep mode.
*
* @note This function will not return.
*/
static void advertising_start(void) {
ret_code_t err_code;
static void sleep_mode_enter(void) {
uint32_t err_code = bsp_indication_set(BSP_INDICATE_IDLE);
APP_ERROR_CHECK(err_code);
err_code = sd_ble_gap_adv_start(m_adv_handle, APP_BLE_CONN_CFG_TAG);
// Prepare wakeup buttons.
err_code = bsp_btn_ble_sleep_mode_prepare();
APP_ERROR_CHECK(err_code);
bsp_board_led_on(ADVERTISING_LED);
// Go to system-off mode (this function will not return; wakeup will cause a
// reset).
err_code = sd_power_system_off();
APP_ERROR_CHECK(err_code);
}
/**@brief Function for handling advertising events.
*
* @details This function will be called for advertising events which are passed
* to the application.
*
* @param[in] ble_adv_evt Advertising event.
*/
static void on_adv_evt(ble_adv_evt_t ble_adv_evt) {
uint32_t err_code;
switch (ble_adv_evt) {
case BLE_ADV_EVT_FAST:
err_code = bsp_indication_set(BSP_INDICATE_ADVERTISING);
APP_ERROR_CHECK(err_code);
break;
case BLE_ADV_EVT_IDLE:
sleep_mode_enter();
break;
default:
break;
}
}
/**@brief Function for handling BLE events.
@ -390,34 +368,22 @@ static void advertising_start(void) {
* @param[in] p_context Unused.
*/
static void ble_evt_handler(ble_evt_t const *p_ble_evt, void *p_context) {
ret_code_t err_code;
uint32_t err_code;
switch (p_ble_evt->header.evt_id) {
case BLE_GAP_EVT_CONNECTED:
NRF_LOG_INFO("Connected");
bsp_board_led_on(CONNECTED_LED);
bsp_board_led_off(ADVERTISING_LED);
err_code = bsp_indication_set(BSP_INDICATE_CONNECTED);
APP_ERROR_CHECK(err_code);
m_conn_handle = p_ble_evt->evt.gap_evt.conn_handle;
err_code = nrf_ble_qwr_conn_handle_assign(&m_qwr, m_conn_handle);
APP_ERROR_CHECK(err_code);
err_code = app_button_enable();
APP_ERROR_CHECK(err_code);
break;
case BLE_GAP_EVT_DISCONNECTED:
NRF_LOG_INFO("Disconnected");
bsp_board_led_off(CONNECTED_LED);
// LED indication will be changed when advertising starts.
m_conn_handle = BLE_CONN_HANDLE_INVALID;
err_code = app_button_disable();
APP_ERROR_CHECK(err_code);
advertising_start();
break;
case BLE_GAP_EVT_SEC_PARAMS_REQUEST:
// Pairing not supported
err_code = sd_ble_gap_sec_params_reply(
m_conn_handle, BLE_GAP_SEC_STATUS_PAIRING_NOT_SUPP, NULL, NULL);
APP_ERROR_CHECK(err_code);
break;
case BLE_GAP_EVT_PHY_UPDATE_REQUEST: {
@ -431,6 +397,13 @@ static void ble_evt_handler(ble_evt_t const *p_ble_evt, void *p_context) {
APP_ERROR_CHECK(err_code);
} break;
case BLE_GAP_EVT_SEC_PARAMS_REQUEST:
// Pairing not supported
err_code = sd_ble_gap_sec_params_reply(
m_conn_handle, BLE_GAP_SEC_STATUS_PAIRING_NOT_SUPP, NULL, NULL);
APP_ERROR_CHECK(err_code);
break;
case BLE_GATTS_EVT_SYS_ATTR_MISSING:
// No system attributes have been stored.
err_code = sd_ble_gatts_sys_attr_set(m_conn_handle, NULL, 0, 0);
@ -439,7 +412,6 @@ static void ble_evt_handler(ble_evt_t const *p_ble_evt, void *p_context) {
case BLE_GATTC_EVT_TIMEOUT:
// Disconnect on GATT Client timeout event.
NRF_LOG_DEBUG("GATT Client Timeout.");
err_code =
sd_ble_gap_disconnect(p_ble_evt->evt.gattc_evt.conn_handle,
BLE_HCI_REMOTE_USER_TERMINATED_CONNECTION);
@ -448,7 +420,6 @@ static void ble_evt_handler(ble_evt_t const *p_ble_evt, void *p_context) {
case BLE_GATTS_EVT_TIMEOUT:
// Disconnect on GATT Server timeout event.
NRF_LOG_DEBUG("GATT Server Timeout.");
err_code =
sd_ble_gap_disconnect(p_ble_evt->evt.gatts_evt.conn_handle,
BLE_HCI_REMOTE_USER_TERMINATED_CONNECTION);
@ -461,9 +432,10 @@ static void ble_evt_handler(ble_evt_t const *p_ble_evt, void *p_context) {
}
}
/**@brief Function for initializing the BLE stack.
/**@brief Function for the SoftDevice initialization.
*
* @details Initializes the SoftDevice and the BLE event interrupt.
* @details This function initializes the SoftDevice and the BLE event
* interrupt.
*/
static void ble_stack_init(void) {
ret_code_t err_code;
@ -486,47 +458,190 @@ static void ble_stack_init(void) {
NULL);
}
/**@brief Function for handling events from the button handler module.
/**@brief Function for handling events from the GATT library. */
void gatt_evt_handler(nrf_ble_gatt_t *p_gatt, nrf_ble_gatt_evt_t const *p_evt) {
if ((m_conn_handle == p_evt->conn_handle) &&
(p_evt->evt_id == NRF_BLE_GATT_EVT_ATT_MTU_UPDATED)) {
m_ble_nus_max_data_len =
p_evt->params.att_mtu_effective - OPCODE_LENGTH - HANDLE_LENGTH;
NRF_LOG_INFO("Data len is set to 0x%X(%d)", m_ble_nus_max_data_len,
m_ble_nus_max_data_len);
}
NRF_LOG_DEBUG("ATT MTU exchange completed. central 0x%x peripheral 0x%x",
p_gatt->att_mtu_desired_central,
p_gatt->att_mtu_desired_periph);
}
/**@brief Function for initializing the GATT library. */
void gatt_init(void) {
ret_code_t err_code;
err_code = nrf_ble_gatt_init(&m_gatt, gatt_evt_handler);
APP_ERROR_CHECK(err_code);
err_code =
nrf_ble_gatt_att_mtu_periph_set(&m_gatt, NRF_SDH_BLE_GATT_MAX_MTU_SIZE);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for handling events from the BSP module.
*
* @param[in] pin_no The pin that the event applies to.
* @param[in] button_action The button action (press/release).
* @param[in] event Event generated by button press.
*/
static void button_event_handler(uint8_t pin_no, uint8_t button_action) {
ret_code_t err_code;
void bsp_event_handler(bsp_event_t event) {
uint32_t err_code;
switch (event) {
case BSP_EVENT_SLEEP:
sleep_mode_enter();
break;
switch (pin_no) {
case LEDBUTTON_BUTTON:
NRF_LOG_INFO("Send button state change.");
err_code = ble_lbs_on_button_change(m_conn_handle, &m_lbs, button_action);
if (err_code != NRF_SUCCESS &&
err_code != BLE_ERROR_INVALID_CONN_HANDLE &&
err_code != NRF_ERROR_INVALID_STATE &&
err_code != BLE_ERROR_GATTS_SYS_ATTR_MISSING) {
case BSP_EVENT_DISCONNECT:
err_code = sd_ble_gap_disconnect(
m_conn_handle, BLE_HCI_REMOTE_USER_TERMINATED_CONNECTION);
if (err_code != NRF_ERROR_INVALID_STATE) {
APP_ERROR_CHECK(err_code);
}
break;
case BSP_EVENT_WHITELIST_OFF:
if (m_conn_handle == BLE_CONN_HANDLE_INVALID) {
err_code = ble_advertising_restart_without_whitelist(&m_advertising);
if (err_code != NRF_ERROR_INVALID_STATE) {
APP_ERROR_CHECK(err_code);
}
}
break;
default:
APP_ERROR_HANDLER(pin_no);
break;
}
}
/**@brief Function for initializing the button handler module.
/**@brief Function for handling app_uart events.
*
* @details This function will receive a single character from the app_uart
* module and append it to a string. The string will be be sent over BLE when
* the last character received was a 'new line' '\n' (hex 0x0A) or if the string
* has reached the maximum data length.
*/
static void buttons_init(void) {
ret_code_t err_code;
/**@snippet [Handling the data received over UART] */
void uart_event_handle(app_uart_evt_t *p_event) {
static uint8_t data_array[BLE_NUS_MAX_DATA_LEN];
static uint8_t index = 0;
uint32_t err_code;
switch (p_event->evt_type) {
case APP_UART_DATA_READY:
UNUSED_VARIABLE(app_uart_get(&data_array[index]));
index++;
if ((index >= 64)) {
if (index > 1) {
NRF_LOG_DEBUG("Ready to send data over BLE NUS");
NRF_LOG_HEXDUMP_DEBUG(data_array, index);
do {
uint16_t length = (uint16_t)index;
err_code =
ble_nus_data_send(&m_nus, data_array, &length, m_conn_handle);
if ((err_code != NRF_ERROR_INVALID_STATE) &&
(err_code != NRF_ERROR_RESOURCES) &&
(err_code != NRF_ERROR_NOT_FOUND)) {
APP_ERROR_CHECK(err_code);
}
} while (err_code == NRF_ERROR_RESOURCES);
}
index = 0;
}
break;
// The array must be static because a pointer to it will be saved in the
// button handler module.
static app_button_cfg_t buttons[] = {
{LEDBUTTON_BUTTON, false, BUTTON_PULL, button_event_handler}};
// case APP_UART_COMMUNICATION_ERROR:
// APP_ERROR_HANDLER(p_event->data.error_communication);
// break;
//
// case APP_UART_FIFO_ERROR:
// APP_ERROR_HANDLER(p_event->data.error_code);
// break;
err_code =
app_button_init(buttons, ARRAY_SIZE(buttons), BUTTON_DETECTION_DELAY);
default:
break;
}
}
/**@snippet [Handling the data received over UART] */
/**@brief Function for initializing the UART module.
*/
/**@snippet [UART Initialization] */
static void uart_init(void) {
uint32_t err_code;
app_uart_comm_params_t const comm_params = {
.rx_pin_no = RX_PIN_NUMBER,
.tx_pin_no = TX_PIN_NUMBER,
.rts_pin_no = RTS_PIN_NUMBER,
.cts_pin_no = CTS_PIN_NUMBER,
.flow_control = APP_UART_FLOW_CONTROL_ENABLED,
.use_parity = false,
#if defined(UART_PRESENT)
.baud_rate = NRF_UART_BAUDRATE_1000000
#else
.baud_rate = NRF_UARTE_BAUDRATE_1000000
#endif
};
APP_UART_FIFO_INIT(&comm_params, UART_RX_BUF_SIZE, UART_TX_BUF_SIZE,
uart_event_handle, APP_IRQ_PRIORITY_LOWEST, err_code);
APP_ERROR_CHECK(err_code);
}
/**@snippet [UART Initialization] */
/**@brief Function for initializing the Advertising functionality.
*/
static void advertising_init(void) {
uint32_t err_code;
ble_advertising_init_t init;
memset(&init, 0, sizeof(init));
init.advdata.name_type = BLE_ADVDATA_FULL_NAME;
init.advdata.include_appearance = false;
init.advdata.flags = BLE_GAP_ADV_FLAGS_LE_ONLY_LIMITED_DISC_MODE;
init.srdata.uuids_complete.uuid_cnt =
sizeof(m_adv_uuids) / sizeof(m_adv_uuids[0]);
init.srdata.uuids_complete.p_uuids = m_adv_uuids;
init.config.ble_adv_fast_enabled = true;
init.config.ble_adv_fast_interval = APP_ADV_INTERVAL;
init.config.ble_adv_fast_timeout = APP_ADV_DURATION;
init.evt_handler = on_adv_evt;
err_code = ble_advertising_init(&m_advertising, &init);
APP_ERROR_CHECK(err_code);
ble_advertising_conn_cfg_tag_set(&m_advertising, APP_BLE_CONN_CFG_TAG);
}
/**@brief Function for initializing buttons and leds.
*
* @param[out] p_erase_bonds Will be true if the clear bonding button was
* pressed to wake the application up.
*/
static void buttons_leds_init(bool *p_erase_bonds) {
bsp_event_t startup_event;
uint32_t err_code =
bsp_init(BSP_INIT_LEDS | BSP_INIT_BUTTONS, bsp_event_handler);
APP_ERROR_CHECK(err_code);
err_code = bsp_btn_ble_init(NULL, &startup_event);
APP_ERROR_CHECK(err_code);
*p_erase_bonds = (startup_event == BSP_EVENT_CLEAR_BONDING_DATA);
}
/**@brief Function for initializing the nrf log module.
*/
static void log_init(void) {
ret_code_t err_code = NRF_LOG_INIT(NULL);
APP_ERROR_CHECK(err_code);
@ -553,14 +668,23 @@ static void idle_state_handle(void) {
}
}
/**@brief Function for application main entry.
/**@brief Function for starting advertising.
*/
static void advertising_start(void) {
uint32_t err_code = ble_advertising_start(&m_advertising, BLE_ADV_MODE_FAST);
APP_ERROR_CHECK(err_code);
}
/**@brief Application main function.
*/
int main(void) {
bool erase_bonds;
// Initialize.
uart_init();
log_init();
leds_init();
timers_init();
buttons_init();
buttons_leds_init(&erase_bonds);
power_management_init();
ble_stack_init();
gap_params_init();
@ -570,7 +694,8 @@ int main(void) {
conn_params_init();
// Start execution.
NRF_LOG_INFO("Blinky example started.");
printf("\r\nUART started.\r\n");
NRF_LOG_INFO("Debug logging for UART over RTT started.");
advertising_start();
// Enter main loop.

@ -6,7 +6,7 @@ GROUP(-lgcc -lc -lnosys)
MEMORY
{
FLASH (rx) : ORIGIN = 0x27000, LENGTH = 0xd9000
RAM (rwx) : ORIGIN = 0x20002300, LENGTH = 0x3dd00
RAM (rwx) : ORIGIN = 0x20002ae8, LENGTH = 0x3d518
}
SECTIONS
@ -57,18 +57,18 @@ SECTIONS
KEEP(*(SORT(.sdh_soc_observers*)))
PROVIDE(__stop_sdh_soc_observers = .);
} > FLASH
.pwr_mgmt_data :
{
PROVIDE(__start_pwr_mgmt_data = .);
KEEP(*(SORT(.pwr_mgmt_data*)))
PROVIDE(__stop_pwr_mgmt_data = .);
} > FLASH
.sdh_ble_observers :
{
PROVIDE(__start_sdh_ble_observers = .);
KEEP(*(SORT(.sdh_ble_observers*)))
PROVIDE(__stop_sdh_ble_observers = .);
} > FLASH
.pwr_mgmt_data :
{
PROVIDE(__start_pwr_mgmt_data = .);
KEEP(*(SORT(.pwr_mgmt_data*)))
PROVIDE(__stop_pwr_mgmt_data = .);
} > FLASH
.sdh_req_observers :
{
PROVIDE(__start_sdh_req_observers = .);

File diff suppressed because it is too large Load Diff

@ -17,7 +17,7 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "dfu/dfu.h"
#include "ble/dfu.h"
/// package: trezorio.ble
@ -65,12 +65,26 @@ STATIC mp_obj_t mod_trezorio_BLE_update_chunk(mp_obj_t data) {
STATIC MP_DEFINE_CONST_FUN_OBJ_1(mod_trezorio_BLE_update_chunk_obj,
mod_trezorio_BLE_update_chunk);
/// def write(self, msg: bytes) -> int:
/// """
/// Sends message using BLE.
/// """
STATIC mp_obj_t mod_trezorio_BLE_write(mp_obj_t self, mp_obj_t msg) {
mp_buffer_info_t buf = {0};
mp_get_buffer_raise(msg, &buf, MP_BUFFER_READ);
ble_comm_send(buf.buf, buf.len);
return MP_OBJ_NEW_SMALL_INT(buf.len);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_2(mod_trezorio_BLE_write_obj,
mod_trezorio_BLE_write);
STATIC const mp_rom_map_elem_t mod_trezorio_BLE_globals_table[] = {
{MP_ROM_QSTR(MP_QSTR___name__), MP_ROM_QSTR(MP_QSTR_ble)},
{MP_ROM_QSTR(MP_QSTR_update_init),
MP_ROM_PTR(&mod_trezorio_BLE_update_init_obj)},
{MP_ROM_QSTR(MP_QSTR_update_chunk),
MP_ROM_PTR(&mod_trezorio_BLE_update_chunk_obj)},
{MP_ROM_QSTR(MP_QSTR_write), MP_ROM_PTR(&mod_trezorio_BLE_write_obj)},
};
STATIC MP_DEFINE_CONST_DICT(mod_trezorio_BLE_globals,
mod_trezorio_BLE_globals_table);

@ -19,6 +19,7 @@
#include <string.h>
#include "ble/comm.h"
#include "button.h"
#include "common.h"
#include "display.h"
@ -27,6 +28,8 @@
#define USB_DATA_IFACE (253)
#define BUTTON_IFACE (254)
#define TOUCH_IFACE (255)
#define USB_RW_IFACE_MAX (15) // 0-15 reserved for USB
#define BLE_IFACE (16)
#define POLL_READ (0x0000)
#define POLL_WRITE (0x0100)
@ -145,30 +148,46 @@ STATIC mp_obj_t mod_trezorio_poll(mp_obj_t ifaces, mp_obj_t list_ref,
}
}
#endif
else if (mode == POLL_READ) {
if (sectrue == usb_hid_can_read(iface)) {
uint8_t buf[64] = {0};
int len = usb_hid_read(iface, buf, sizeof(buf));
if (len > 0) {
else if (iface <= USB_RW_IFACE_MAX) {
if (mode == POLL_READ) {
if (sectrue == usb_hid_can_read(iface)) {
uint8_t buf[64] = {0};
int len = usb_hid_read(iface, buf, sizeof(buf));
if (len > 0) {
ret->items[0] = MP_OBJ_NEW_SMALL_INT(i);
ret->items[1] = mp_obj_new_bytes(buf, len);
return mp_const_true;
}
} else if (sectrue == usb_webusb_can_read(iface)) {
uint8_t buf[64] = {0};
int len = usb_webusb_read(iface, buf, sizeof(buf));
if (len > 0) {
ret->items[0] = MP_OBJ_NEW_SMALL_INT(i);
ret->items[1] = mp_obj_new_bytes(buf, len);
return mp_const_true;
}
}
} else if (mode == POLL_WRITE) {
if (sectrue == usb_hid_can_write(iface)) {
ret->items[0] = MP_OBJ_NEW_SMALL_INT(i);
ret->items[1] = mp_obj_new_bytes(buf, len);
ret->items[1] = mp_const_none;
return mp_const_true;
} else if (sectrue == usb_webusb_can_write(iface)) {
ret->items[0] = MP_OBJ_NEW_SMALL_INT(i);
ret->items[1] = mp_const_none;
return mp_const_true;
}
} else if (sectrue == usb_webusb_can_read(iface)) {
}
} else if (iface == BLE_IFACE) {
if (mode == POLL_READ) {
uint8_t buf[64] = {0};
int len = usb_webusb_read(iface, buf, sizeof(buf));
int len = ble_int_comm_receive(buf, sizeof(buf), &ble_last_internal);
if (len > 0) {
ret->items[0] = MP_OBJ_NEW_SMALL_INT(i);
ret->items[1] = mp_obj_new_bytes(buf, len);
return mp_const_true;
}
}
} else if (mode == POLL_WRITE) {
if (sectrue == usb_hid_can_write(iface)) {
ret->items[0] = MP_OBJ_NEW_SMALL_INT(i);
ret->items[1] = mp_const_none;
return mp_const_true;
} else if (sectrue == usb_webusb_can_write(iface)) {
} else if (mode == POLL_WRITE) {
ret->items[0] = MP_OBJ_NEW_SMALL_INT(i);
ret->items[1] = mp_const_none;
return mp_const_true;

@ -76,7 +76,7 @@ bool usb_connected_previously = true;
/// USB_CHECK: int # interface id for check of USB data connection
/// WireInterface = Union[HID, WebUSB]
/// WireInterface = Union[HID, WebUSB, BleInterface]
STATIC const mp_rom_map_elem_t mp_module_trezorio_globals_table[] = {
{MP_ROM_QSTR(MP_QSTR___name__), MP_ROM_QSTR(MP_QSTR_trezorio)},

@ -72,7 +72,7 @@
#ifdef USE_SECP256K1_ZKP
#include "zkp_context.h"
#include "dfu/dfu.h"
#include "ble/comm.h"
#endif
@ -145,7 +145,7 @@ int main(void) {
sdcard_init();
#endif
dfu_init();
ble_comm_init();
#if !defined TREZOR_MODEL_1
// jump to unprivileged mode

@ -0,0 +1,67 @@
/*
* This file is part of the Trezor project, https://trezor.io/
*
* Copyright (c) SatoshiLabs
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include STM32_HAL_H
#include TREZOR_BOARD
static UART_HandleTypeDef urt;
void ble_comm_init(void) {
GPIO_InitTypeDef GPIO_InitStructure;
__HAL_RCC_USART1_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
GPIO_InitStructure.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12;
GPIO_InitStructure.Mode = GPIO_MODE_AF_PP;
GPIO_InitStructure.Pull = GPIO_NOPULL;
GPIO_InitStructure.Alternate = GPIO_AF7_USART1;
GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStructure);
urt.Init.Mode = UART_MODE_TX_RX;
urt.Init.BaudRate = 1000000;
urt.Init.HwFlowCtl = UART_HWCONTROL_RTS_CTS;
urt.Init.OverSampling = UART_OVERSAMPLING_16;
urt.Init.Parity = UART_PARITY_NONE, urt.Init.StopBits = UART_STOPBITS_1;
urt.Init.WordLength = UART_WORDLENGTH_8B;
urt.Instance = USART1;
HAL_UART_Init(&urt);
}
void ble_comm_send(uint8_t *data, uint32_t len) {
HAL_UART_Transmit(&urt, data, len, 10);
}
uint32_t ble_comm_receive(uint8_t *data, uint32_t len) {
if (urt.Instance->SR & USART_SR_RXNE) {
HAL_StatusTypeDef result = HAL_UART_Receive(&urt, data, len, 30);
if (result == HAL_OK) {
return len;
} else {
if (urt.RxXferCount == len) {
return 0;
}
return len - urt.RxXferCount - 1;
}
}
return 0;
}

@ -0,0 +1,7 @@
void ble_comm_init(void);
void ble_comm_send(uint8_t *data, uint32_t len);
uint32_t ble_comm_receive(uint8_t *data, uint32_t len);

@ -0,0 +1,129 @@
/*
* This file is part of the Trezor project, https://trezor.io/
*
* Copyright (c) SatoshiLabs
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include STM32_HAL_H
#include "dfu.h"
#include "comm.h"
#include "fwu.h"
static TFwu sFwu;
static uint32_t tick_start = 0;
void txFunction(struct SFwu *fwu, uint8_t *buf, uint8_t len);
static uint8_t readData(uint8_t *data, int maxLen);
void dfu_init(void) {}
dfu_result_t dfu_update_process(void) {
while (1) {
// Can send 4 chars...
// (On a microcontroller, you'd use the TX Empty interrupt or test a
// register.)
fwuCanSendData(&sFwu, 4);
// Data available? Get up to 4 bytes...
// (On a microcontroller, you'd use the RX Available interrupt or test a
// register.)
uint8_t rxBuf[4];
uint8_t rxLen = readData(rxBuf, 4);
if (rxLen > 0) {
fwuDidReceiveData(&sFwu, rxBuf, rxLen);
}
// Give the firmware update module a timeslot to continue the process.
EFwuProcessStatus status = fwuYield(&sFwu, 0);
if (status == FWU_STATUS_COMPLETION) {
return DFU_SUCCESS;
}
if (status == FWU_STATUS_FAILURE) {
return DFU_FAIL;
}
if (HAL_GetTick() - tick_start > 2000) {
return DFU_FAIL;
}
if (fwuIsReadyForChunk(&sFwu)) {
return DFU_NEXT_CHUNK;
}
}
}
dfu_result_t dfu_update_init(uint8_t *data, uint32_t len, uint32_t binary_len) {
sFwu.commandObject = data;
sFwu.commandObjectLen = len;
sFwu.dataObject = NULL;
sFwu.dataObjectLen = binary_len;
sFwu.txFunction = txFunction;
sFwu.responseTimeoutMillisec = 2000;
tick_start = HAL_GetTick();
// Prepare the firmware update process.
fwuInit(&sFwu);
// Start the firmware update process.
fwuExec(&sFwu);
return dfu_update_process();
}
dfu_result_t dfu_update_chunk(uint8_t *data, uint32_t len) {
tick_start = HAL_GetTick();
fwuSendChunk(&sFwu, data, len);
return dfu_update_process();
}
dfu_result_t dfu_update_do(uint8_t *datfile, uint32_t datfile_len,
uint8_t *binfile, uint32_t binfile_len) {
uint32_t chunk_offset = 0;
uint32_t rem_data = binfile_len;
dfu_result_t res = dfu_update_init(datfile, datfile_len, binfile_len);
while (res == DFU_NEXT_CHUNK) {
// Send the next chunk of the data object.
uint32_t chunk_size = 4096;
if (rem_data < 4096) {
chunk_size = rem_data;
rem_data = 0;
} else {
rem_data -= 4096;
}
res = dfu_update_chunk(&binfile[chunk_offset], chunk_size);
chunk_offset += chunk_size;
}
return res;
}
void txFunction(struct SFwu *fwu, uint8_t *buf, uint8_t len) {
ble_comm_send(buf, len);
;
}
static uint8_t readData(uint8_t *data, int maxLen) {
return ble_comm_receive(data, maxLen);
}

@ -1,176 +0,0 @@
//
// main.c
// nrf52-dfu
//
// Sample host application to demonstrate the usage of our C library for the
// Nordic firmware update protocol.
//
// Created by Andreas Schweizer on 30.11.2018.
// Copyright © 2018-2019 Classy Code GmbH
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
// SOFTWARE.
//
#include STM32_HAL_H
#include "dfu.h"
#include "fwu.h"
static TFwu sFwu;
static UART_HandleTypeDef urt;
static uint32_t tick_start = 0;
void txFunction(struct SFwu *fwu, uint8_t *buf, uint8_t len);
static uint8_t readData(uint8_t *data, int maxLen);
void dfu_init(void) {
GPIO_InitTypeDef GPIO_InitStructure;
__HAL_RCC_USART1_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
GPIO_InitStructure.Pin = GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12;
GPIO_InitStructure.Mode = GPIO_MODE_AF_PP;
GPIO_InitStructure.Pull = GPIO_NOPULL;
GPIO_InitStructure.Alternate = GPIO_AF7_USART1;
GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStructure);
urt.Init.Mode = UART_MODE_TX_RX;
urt.Init.BaudRate = 115200;
urt.Init.HwFlowCtl = UART_HWCONTROL_RTS_CTS;
urt.Init.OverSampling = UART_OVERSAMPLING_16;
urt.Init.Parity = UART_PARITY_NONE, urt.Init.StopBits = UART_STOPBITS_1;
urt.Init.WordLength = UART_WORDLENGTH_8B;
urt.Instance = USART1;
HAL_UART_Init(&urt);
// sFwu.commandObject = datfile;
// sFwu.commandObjectLen = sizeof(datfile);
// sFwu.dataObject = NULL;
// sFwu.dataObjectLen = sizeof(binfile);
// sFwu.txFunction = txFunction;
// sFwu.responseTimeoutMillisec = 5000;
}
dfu_result_t dfu_update_process(void) {
while (1) {
// Can send 4 chars...
// (On a microcontroller, you'd use the TX Empty interrupt or test a
// register.)
fwuCanSendData(&sFwu, 4);
// Data available? Get up to 4 bytes...
// (On a microcontroller, you'd use the RX Available interrupt or test a
// register.)
uint8_t rxBuf[4];
uint8_t rxLen = readData(rxBuf, 4);
if (rxLen > 0) {
fwuDidReceiveData(&sFwu, rxBuf, rxLen);
}
// Give the firmware update module a timeslot to continue the process.
EFwuProcessStatus status = fwuYield(&sFwu, 0);
if (status == FWU_STATUS_COMPLETION) {
return DFU_SUCCESS;
}
if (status == FWU_STATUS_FAILURE) {
return DFU_FAIL;
}
if (HAL_GetTick() - tick_start > 2000) {
return DFU_FAIL;
}
if (fwuIsReadyForChunk(&sFwu)) {
return DFU_NEXT_CHUNK;
}
}
}
dfu_result_t dfu_update_init(uint8_t *data, uint32_t len, uint32_t binary_len) {
sFwu.commandObject = data;
sFwu.commandObjectLen = len;
sFwu.dataObject = NULL;
sFwu.dataObjectLen = binary_len;
sFwu.txFunction = txFunction;
sFwu.responseTimeoutMillisec = 2000;
tick_start = HAL_GetTick();
// Prepare the firmware update process.
fwuInit(&sFwu);
// Start the firmware update process.
fwuExec(&sFwu);
return dfu_update_process();
}
dfu_result_t dfu_update_chunk(uint8_t *data, uint32_t len) {
tick_start = HAL_GetTick();
fwuSendChunk(&sFwu, data, len);
return dfu_update_process();
}
dfu_result_t dfu_update_do(uint8_t *datfile, uint32_t datfile_len,
uint8_t *binfile, uint32_t binfile_len) {
uint32_t chunk_offset = 0;
uint32_t rem_data = binfile_len;
dfu_result_t res = dfu_update_init(datfile, datfile_len, binfile_len);
while (res == DFU_NEXT_CHUNK) {
// Send the next chunk of the data object.
uint32_t chunk_size = 4096;
if (rem_data < 4096) {
chunk_size = rem_data;
rem_data = 0;
} else {
rem_data -= 4096;
}
res = dfu_update_chunk(&binfile[chunk_offset], chunk_size);
chunk_offset += chunk_size;
}
return res;
}
void txFunction(struct SFwu *fwu, uint8_t *buf, uint8_t len) {
HAL_UART_Transmit(&urt, buf, len, 10);
}
static uint8_t readData(uint8_t *data, int maxLen) {
HAL_StatusTypeDef result = HAL_UART_Receive(&urt, data, maxLen, 0);
if (result == HAL_OK) {
return maxLen;
} else {
if (urt.RxXferCount == maxLen) {
return 0;
}
return maxLen - urt.RxXferCount - 1;
}
}

@ -0,0 +1,7 @@
#include <stdint.h>
void ble_comm_init(void) {}
void ble_comm_send(uint8_t *data, uint32_t len) {}
uint32_t ble_comm_receive(uint8_t *data, uint32_t len) { return 0; }

@ -0,0 +1,6 @@
void ble_comm_init(void);
void ble_comm_send(uint8_t *data, uint32_t len);
uint32_t ble_comm_receive(uint8_t *data, uint32_t len);

@ -203,4 +203,4 @@ BUTTON_RELEASED: int # button up event
BUTTON_LEFT: int # button number of left button
BUTTON_RIGHT: int # button number of right button
USB_CHECK: int # interface id for check of USB data connection
WireInterface = Union[HID, WebUSB]
WireInterface = Union[HID, WebUSB, BleInterface]

@ -0,0 +1,22 @@
from typing import *
# extmod/modtrezorio/modtrezorio-ble.h
def update_init(data: bytes, binsize: int) -> int:
"""
Initializes the BLE firmware update
"""
# extmod/modtrezorio/modtrezorio-ble.h
def update_chunk(chunk: bytes) -> int:
"""
Writes next chunk of BLE firmware update
"""
# extmod/modtrezorio/modtrezorio-ble.h
def write(self, msg: bytes) -> int:
"""
Sends message using BLE.
"""

@ -33,6 +33,8 @@ from trezor import utils
all_modules
import all_modules
bluetooth
import bluetooth
boot
import boot
main

@ -0,0 +1,17 @@
from trezorio import ble
class BleInterface:
def __init__(self):
pass
def iface_num(self) -> int:
return 16
def write(self, msg: bytes) -> int:
return ble.write(self, msg)
# interface used for trezor wire protocol
iface_ble = BleInterface()

@ -1,6 +1,7 @@
from trezor import log, loop, utils, wire, workflow
import apps.base
import bluetooth
import usb
apps.base.boot()
@ -23,6 +24,7 @@ workflow.start_default()
wire.setup(usb.iface_wire)
if __debug__:
wire.setup(usb.iface_debug, is_debug_session=True)
wire.setup(bluetooth.iface_ble)
loop.run()

@ -16,10 +16,15 @@
import functools
import sys
import threading
from contextlib import contextmanager
from typing import TYPE_CHECKING, Any, Callable, Dict, Optional
import click
import dbus
import dbus.mainloop.glib
import dbus.service
from gi.repository import GLib
from .. import exceptions, transport
from ..client import TrezorClient
@ -134,20 +139,36 @@ def with_client(func: "Callable[Concatenate[TrezorClient, P], R]") -> "Callable[
def trezorctl_command_with_client(
obj: TrezorConnection, *args: "P.args", **kwargs: "P.kwargs"
) -> "R":
with obj.client_context() as client:
session_was_resumed = obj.session_id == client.session_id
if not session_was_resumed and obj.session_id is not None:
# tried to resume but failed
click.echo("Warning: failed to resume session.", err=True)
loop = GLib.MainLoop()
dbus.mainloop.glib.DBusGMainLoop(set_as_default=True)
def callback_wrapper():
try:
return func(client, *args, **kwargs)
finally:
if not session_was_resumed:
with obj.client_context() as client:
session_was_resumed = obj.session_id == client.session_id
if not session_was_resumed and obj.session_id is not None:
# tried to resume but failed
click.echo("Warning: failed to resume session.", err=True)
try:
client.end_session()
except Exception:
pass
return func(client, *args, **kwargs)
except Exception as e:
print(e)
finally:
if not session_was_resumed:
try:
client.end_session()
except Exception:
pass
except Exception as e:
print(e)
finally:
loop.quit()
threading.Thread(target=callback_wrapper, daemon=True).start()
loop.run()
return None
# the return type of @click.pass_obj is improperly specified and pyright doesn't
# understand that it converts f(obj, *args, **kwargs) to f(*args, **kwargs)

@ -0,0 +1,452 @@
#!/usr/bin/python3
import queue
import threading
import time
import dbus
import dbus.mainloop.glib
import dbus.service
class NotConnectedError(Exception):
pass
class DBusInvalidArgsException(dbus.exceptions.DBusException):
_dbus_error_name = "org.freedesktop.DBus.Error.InvalidArgs"
def format_uuid(uuid):
if type(uuid) == int:
if uuid > 0xFFFF:
raise ValueError("32-bit UUID not supported yet")
uuid = "%04X" % uuid
return uuid
class TealBlue:
def __init__(self):
self._bus = dbus.SystemBus()
self._bluez = dbus.Interface(
self._bus.get_object("org.bluez", "/"), "org.freedesktop.DBus.ObjectManager"
)
def find_adapter(self):
# find the first adapter
objects = self._bluez.GetManagedObjects()
for path in sorted(objects.keys()):
interfaces = objects[path]
if "org.bluez.Adapter1" not in interfaces:
continue
properties = interfaces["org.bluez.Adapter1"]
return Adapter(self, path, properties)
return None # no adapter found
# copied from:
# https://github.com/adafruit/Adafruit_Python_BluefruitLE/blob/master/Adafruit_BluefruitLE/bluez_dbus/provider.py
def _print_tree(self):
"""Print tree of all bluez objects, useful for debugging."""
# This is based on the bluez sample code get-managed-objects.py.
objects = self._bluez.GetManagedObjects()
for path in sorted(objects.keys()):
print("[ %s ]" % (path))
interfaces = objects[path]
for interface in sorted(interfaces.keys()):
if interface in [
"org.freedesktop.DBus.Introspectable",
"org.freedesktop.DBus.Properties",
]:
continue
print(" %s" % (interface))
properties = interfaces[interface]
for key in sorted(properties.keys()):
print(" %s = %s" % (key, properties[key]))
class Adapter:
def __init__(self, teal, path, properties):
self._teal = teal
self._path = path
self._properties = properties
self._object = dbus.Interface(
teal._bus.get_object("org.bluez", path), "org.bluez.Adapter1"
)
self._advertisement = None
def __repr__(self):
return "<tealblue.Adapter address=%s>" % (self._properties["Address"])
def devices(self):
"""
Returns the devices that BlueZ has discovered.
"""
objects = self._teal._bluez.GetManagedObjects()
for path in sorted(objects.keys()):
interfaces = objects[path]
if "org.bluez.Device1" not in interfaces:
continue
properties = interfaces["org.bluez.Device1"]
yield Device(self._teal, path, properties)
def scan(self, timeout_s):
return Scanner(self._teal, self, self.devices(), timeout_s)
@property
def advertisement(self):
if self._advertisement is None:
self._advertisement = Advertisement(self._teal, self)
return self._advertisement
def advertise(self, enable):
if enable:
self.advertisement.enable()
else:
self.advertisement.disable()
def advertise_data(
self,
local_name=None,
service_data=None,
service_uuids=None,
manufacturer_data=None,
):
self.advertisement.local_name = local_name
self.advertisement.service_data = service_data
self.advertisement.service_uuids = service_uuids
self.advertisement.manufacturer_data = manufacturer_data
class Scanner:
def __init__(self, teal, adapter, initial_devices, timeout_s):
self._teal = teal
self._adapter = adapter
self._was_discovering = adapter._properties[
"Discovering"
] # TODO get current value, or watch property changes
self._queue = queue.Queue()
self.timeout_s = timeout_s
for device in initial_devices:
self._queue.put(device)
def new_device(path, interfaces):
if "org.bluez.Device1" not in interfaces:
return
if not path.startswith(self._adapter._path + "/"):
return
# properties = interfaces["org.bluez.Device1"]
self._queue.put(Device(self._teal, path, interfaces["org.bluez.Device1"]))
self._signal_receiver = self._teal._bus.add_signal_receiver(
new_device,
dbus_interface="org.freedesktop.DBus.ObjectManager",
signal_name="InterfacesAdded",
)
if not self._was_discovering:
self._adapter._object.StartDiscovery()
def __enter__(self):
return self
def __exit__(self, type, value, traceback):
if not self._was_discovering:
self._adapter._object.StopDiscovery()
self._signal_receiver.remove()
def __iter__(self):
return self
def __next__(self):
try:
return self._queue.get(timeout=self.timeout_s)
except queue.Empty:
raise StopIteration
class Device:
def __init__(self, teal, path, properties):
self._teal = teal
self._path = path
self._properties = properties
self._services_resolved = threading.Event()
self._services = None
if properties["ServicesResolved"]:
self._services_resolved.set()
# Listen to device events (connect, disconnect, ServicesResolved, ...)
self._device = dbus.Interface(
teal._bus.get_object("org.bluez", path), "org.bluez.Device1"
)
self._device_props = dbus.Interface(
self._device, "org.freedesktop.DBus.Properties"
)
self._signal_receiver = self._device_props.connect_to_signal(
"PropertiesChanged",
lambda itf, ch, inv: self._on_prop_changed(itf, ch, inv),
)
def __del__(self):
self._signal_receiver.remove()
def __repr__(self):
return "<tealblue.Device address=%s name=%r>" % (self.address, self.name)
def _on_prop_changed(self, properties, changed_props, invalidated_props):
for key, value in changed_props.items():
self._properties[key] = value
if "ServicesResolved" in changed_props:
if changed_props["ServicesResolved"]:
self._services_resolved.set()
else:
self._services_resolved.clear()
def _wait_for_discovery(self):
# wait until ServicesResolved is True
self._services_resolved.wait()
def connect(self):
self._device.Connect()
def disconnect(self):
self._device.Disconnect()
def resolve_services(self):
self._services_resolved.wait()
@property
def services(self):
if not self._services_resolved.is_set():
return None
if self._services is None:
self._services = {}
objects = self._teal._bluez.GetManagedObjects()
for path in sorted(objects.keys()):
if not path.startswith(self._path + "/"):
continue
if "org.bluez.GattService1" in objects[path]:
properties = objects[path]["org.bluez.GattService1"]
service = Service(self._teal, self, path, properties)
self._services[service.uuid] = service
elif "org.bluez.GattCharacteristic1" in objects[path]:
properties = objects[path]["org.bluez.GattCharacteristic1"]
characterstic = Characteristic(self._teal, self, path, properties)
for service in self._services.values():
if properties["Service"] == service._path:
service.characteristics[characterstic.uuid] = characterstic
return self._services
@property
def connected(self):
return bool(self._properties["Connected"])
@property
def services_resolved(self):
return bool(self._properties["ServicesResolved"])
@property
def UUIDs(self):
return [str(s) for s in self._properties["UUIDs"]]
@property
def address(self):
return str(self._properties["Address"])
@property
def name(self):
if "Name" not in self._properties:
return None
return str(self._properties["Name"])
@property
def alias(self):
if "Alias" not in self._properties:
return None
return str(self._properties["Alias"])
class Service:
def __init__(self, teal, device, path, properties):
self._device = device
self._teal = teal
self._path = path
self._properties = properties
self.characteristics = {}
def __repr__(self):
return "<tealblue.Service device=%s uuid=%s>" % (
self._device.address,
self.uuid,
)
@property
def uuid(self):
return str(self._properties["UUID"])
class Characteristic:
def __init__(self, teal, device, path, properties):
self._device = device
self._teal = teal
self._path = path
self._properties = properties
self.on_notify = None
self._char = dbus.Interface(
teal._bus.get_object("org.bluez", path), "org.bluez.GattCharacteristic1"
)
char_props = dbus.Interface(self._char, "org.freedesktop.DBus.Properties")
self._signal_receiver = char_props.connect_to_signal(
"PropertiesChanged",
lambda itf, ch, inv: self._on_prop_changed(itf, ch, inv),
)
def __repr__(self):
return "<tealblue.Characteristic device=%s uuid=%s>" % (
self._device.address,
self.uuid,
)
def __del__(self):
self._signal_receiver.remove()
def _on_prop_changed(self, properties, changed_props, invalidated_props):
for key, value in changed_props.items():
self._properties[key] = bytes(value)
if "Value" in changed_props and self.on_notify is not None:
self.on_notify(self, changed_props["Value"])
def read(self):
return bytes(self._char.ReadValue({}))
def write(self, value):
start = time.time()
try:
self._char.WriteValue(value, {})
except dbus.DBusException as e:
if (
e.get_dbus_name() == "org.bluez.Error.Failed"
and e.get_dbus_message() == "Not connected"
):
raise NotConnectedError()
else:
raise # some other error
# Workaround: if the write took very long, it is possible the connection
# broke (without causing an exception). So check whether we are still
# connected.
# I think this is a bug in BlueZ.
if time.time() - start > 0.5:
if not self._device._device_props.Get("org.bluez.Device1", "Connected"):
raise NotConnectedError()
def start_notify(self):
self._char.StartNotify()
def stop_notify(self):
self._char.StopNotify()
@property
def uuid(self):
return str(self._properties["UUID"])
class Advertisement(dbus.service.Object):
PATH = "/com/github/aykevl/pynus/advertisement"
def __init__(self, teal, adapter):
self._teal = teal
self._adapter = adapter
self._enabled = False
self.service_uuids = None
self.manufacturer_data = None
self.solicit_uuids = None
self.service_data = None
self.local_name = None
self.include_tx_power = None
self._manager = dbus.Interface(
teal._bus.get_object("org.bluez", self._adapter._path),
"org.bluez.LEAdvertisingManager1",
)
self._adv_enabled = threading.Event()
dbus.service.Object.__init__(self, teal._bus, self.PATH)
def enable(self):
if self._enabled:
return
self._manager.RegisterAdvertisement(
dbus.ObjectPath(self.PATH),
dbus.Dictionary({}, signature="sv"),
reply_handler=self._cb_enabled,
error_handler=self._cb_enabled_err,
)
self._adv_enabled.wait()
self._adv_enabled.clear()
def _cb_enabled(self):
self._enabled = True
if self._adv_enabled.is_set():
raise RuntimeError("called enable() twice")
self._adv_enabled.set()
def _cb_enabled_err(self, err):
self._enabled = False
if self._adv_enabled.is_set():
raise RuntimeError("called enable() twice")
self._adv_enabled.set()
def disable(self):
if not self._enabled:
return
self._bus.UnregisterAdvertisement(self.PATH)
self._enabled = False
@property
def enabled(self):
return self._enabled
@dbus.service.method(
"org.freedesktop.DBus.Properties", in_signature="s", out_signature="a{sv}"
)
def GetAll(self, interface):
print("GetAll")
if interface != "org.bluez.LEAdvertisement1":
raise DBusInvalidArgsException()
try:
properties = {
"Type": dbus.String("peripheral"),
}
if self.service_uuids is not None:
properties["ServiceUUIDs"] = dbus.Array(
map(format_uuid, self.service_uuids), signature="s"
)
if self.solicit_uuids is not None:
properties["SolicitUUIDs"] = dbus.Array(
map(format_uuid, self.solicit_uuids), signature="s"
)
if self.manufacturer_data is not None:
properties["ManufacturerData"] = dbus.Dictionary(
{k: v for k, v in self.manufacturer_data.items()}, signature="qv"
)
if self.service_data is not None:
properties["ServiceData"] = dbus.Dictionary(
self.service_data, signature="sv"
)
if self.local_name is not None:
properties["LocalName"] = dbus.String(self.local_name)
if self.include_tx_power is not None:
properties["IncludeTxPower"] = dbus.Boolean(self.include_tx_power)
except Exception as e:
print("err: ", e)
print("properties:", properties)
return properties
@dbus.service.method(
"org.bluez.LEAdvertisement1", in_signature="", out_signature=""
)
def Release(self):
self._enabled = True

@ -117,12 +117,14 @@ def all_transports() -> Iterable[Type["Transport"]]:
from .hid import HidTransport
from .udp import UdpTransport
from .webusb import WebUsbTransport
from .ble import BleTransport
transports: Tuple[Type["Transport"], ...] = (
BridgeTransport,
HidTransport,
UdpTransport,
WebUsbTransport,
BleTransport,
)
return set(t for t in transports if t.ENABLED)

@ -0,0 +1,155 @@
# This file is part of the Trezor project.
#
# Copyright (C) 2012-2022 SatoshiLabs and contributors
#
# This library is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License version 3
# as published by the Free Software Foundation.
#
# This library is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the License along with this library.
# If not, see <https://www.gnu.org/licenses/lgpl-3.0.html>.
import logging
from queue import Queue
from typing import TYPE_CHECKING, Iterable, Optional
from .. import tealblue
from . import TransportException
from .protocol import ProtocolBasedTransport, ProtocolV1
if TYPE_CHECKING:
from ..models import TrezorModel
LOG = logging.getLogger(__name__)
NUS_SERVICE_UUID = "6e400001-b5a3-f393-e0a9-e50e24dcca9e"
NUS_CHARACTERISTIC_RX = "6e400002-b5a3-f393-e0a9-e50e24dcca9e"
NUS_CHARACTERISTIC_TX = "6e400003-b5a3-f393-e0a9-e50e24dcca9e"
def scan_device(adapter, devices):
with adapter.scan(2) as scanner:
for device in scanner:
if NUS_SERVICE_UUID in device.UUIDs:
if device.address not in [d.address for d in devices]:
print(f"Found device: {device.name}, {device.address}")
devices.append(device)
return devices
def lookup_device(adapter):
devices = []
for device in adapter.devices():
if NUS_SERVICE_UUID in device.UUIDs:
devices.append(device)
return devices
class BleTransport(ProtocolBasedTransport):
ENABLED = True
PATH_PREFIX = "ble"
def __init__(self, mac_addr: str, adapter) -> None:
self.tx = None
self.rx = None
self.device = mac_addr
self.adapter = adapter
self.received_data = Queue()
devices = lookup_device(self.adapter)
for d in devices:
if d.address == mac_addr:
self.ble_device = d
break
super().__init__(protocol=ProtocolV1(self))
def get_path(self) -> str:
return "{}:{}".format(self.PATH_PREFIX, self.device)
def find_debug(self) -> "BleTransport":
mac = self.device
return BleTransport(f"{mac}")
@classmethod
def enumerate(
cls, _models: Optional[Iterable["TrezorModel"]] = None
) -> Iterable["BleTransport"]:
adapter = tealblue.TealBlue().find_adapter()
devices = lookup_device(adapter)
devices = [d for d in devices if d.connected]
if len(devices) == 0:
print("Scanning...")
devices = scan_device(adapter, devices)
print("Found %d devices" % len(devices))
for device in devices:
print(f"Device: {device.name}, {device.address}")
return [BleTransport(device.address, adapter) for device in devices]
# @classmethod
# def find_by_path(cls, path: str, prefix_search: bool = False) -> "BleTransport":
# try:
# path = path.replace(f"{cls.PATH_PREFIX}:", "")
# return cls._try_path(path)
# except TransportException:
# if not prefix_search:
# raise
#
# if prefix_search:
# return super().find_by_path(path, prefix_search)
# else:
# raise TransportException(f"No UDP device at {path}")
def open(self) -> None:
if not self.ble_device.connected:
print(
"Connecting to %s (%s)..."
% (self.ble_device.name, self.ble_device.address)
)
self.ble_device.connect()
else:
print(
"Connected to %s (%s)."
% (self.ble_device.name, self.ble_device.address)
)
if not self.ble_device.services_resolved:
print("Resolving services...")
self.ble_device.resolve_services()
service = self.ble_device.services[NUS_SERVICE_UUID]
self.rx = service.characteristics[NUS_CHARACTERISTIC_RX]
self.tx = service.characteristics[NUS_CHARACTERISTIC_TX]
def on_notify(characteristic, value):
self.received_data.put(bytes(value))
self.tx.on_notify = on_notify
self.tx.start_notify()
def close(self) -> None:
pass
def write_chunk(self, chunk: bytes) -> None:
assert self.rx is not None
self.rx.write(chunk)
def read_chunk(self) -> bytes:
assert self.tx is not None
chunk = self.received_data.get()
# LOG.log(DUMP_PACKETS, f"received packet: {chunk.hex()}")
if len(chunk) != 64:
raise TransportException(f"Unexpected chunk size: {len(chunk)}")
return bytearray(chunk)

@ -61,6 +61,8 @@ class WebUsbHandle:
self.handle.claimInterface(self.interface)
except usb1.USBErrorAccess as e:
raise DeviceIsBusy(self.device) from e
except usb1.USBErrorBusy as e:
raise DeviceIsBusy(self.device) from e
def close(self) -> None:
if self.handle is not None:

Loading…
Cancel
Save