Upgraded SDK to v5.1.2

This commit is contained in:
demik 2023-12-28 21:40:18 +01:00
parent 17be92fec7
commit 8dd60e2d20
10 changed files with 1198 additions and 592 deletions

View File

@ -10,4 +10,4 @@ set(include_dirs ".")
idf_component_register(SRCS "${srcs}"
INCLUDE_DIRS "${include_dirs}"
REQUIRES esp_hid)
REQUIRES driver esp_hid nvs_flash spi_flash)

View File

@ -1,63 +1,13 @@
diff --git a/components/esp_hid/include/esp_hidh.h b/components/esp_hid/include/esp_hidh.h
index b1a8264307..d3d1002103 100644
--- a/components/esp_hid/include/esp_hidh.h
+++ b/components/esp_hid/include/esp_hidh.h
@@ -100,6 +100,7 @@ typedef union {
typedef struct {
esp_event_handler_t callback;
+ uint16_t event_stack_size;
} esp_hidh_config_t;
/**
diff --git a/components/esp_hid/src/ble_hidh.c b/components/esp_hid/src/ble_hidh.c
index 5fe54f2fa7..a56eb04c44 100644
--- a/components/esp_hid/src/ble_hidh.c
+++ b/components/esp_hid/src/ble_hidh.c
@@ -617,7 +617,7 @@ esp_err_t esp_ble_hidh_init(const esp_hidh_config_t *config)
.queue_size = 5,
.task_name = "esp_ble_hidh_events",
.task_priority = uxTaskPriorityGet(NULL),
- .task_stack_size = 2048,
+ .task_stack_size = config->event_stack_size > 0 ? config->event_stack_size : 2048,
.task_core_id = tskNO_AFFINITY
};
ret = esp_event_loop_create(&event_task_args, &event_loop_handle);
diff --git a/components/esp_hid/src/bt_hidh.c b/components/esp_hid/src/bt_hidh.c
index 1a17e6aa35..16fae9e65a 100644
index 6f0410e302..59dfc0b07f 100644
--- a/components/esp_hid/src/bt_hidh.c
+++ b/components/esp_hid/src/bt_hidh.c
@@ -320,7 +320,7 @@ esp_err_t esp_bt_hidh_init(const esp_hidh_config_t *config)
.queue_size = 5,
.task_name = "esp_bt_hidh_events",
.task_priority = uxTaskPriorityGet(NULL),
- .task_stack_size = 2048,
+ .task_stack_size = config->event_stack_size > 0 ? config->event_stack_size : 2048,
.task_core_id = tskNO_AFFINITY
};
esp_err_t ret = esp_event_loop_create(&event_task_args, &event_loop_handle);
@@ -386,6 +386,24 @@ void bta_hh_co_data(uint8_t handle, uint8_t *p_rpt, uint16_t len, tBTA_HH_PROTO_
ESP_LOGE(TAG, "Device Not Found: handle %u", handle);
return;
}
+
+ /*
+ * quack patch: mode is always ESP_HID_PROTOCOL_MODE_BOOT even if the device is in BOOT mode
+ * BTA_HH_PROTO_RPT_MODE from Bluedroid is 0
+ * BOOT report id is also questionable, assume than an REPORT mode with a lengh of 3 or 4 is a BOOT packet
+ */
+
+ if (len >= 2 + 1 && p_rpt[0] == 2 && mode == 0) {
+ esp_hidh_event_data_t p = {0};
+ p.input.dev = dev;
+ p.feature.report_id = 2;
+ p.feature.usage = ESP_HID_USAGE_MOUSE;
+ p.feature.data = p_rpt + 1;
+ p.input.length = len - 1;
+ esp_event_post_to(event_loop_handle, ESP_HIDH_EVENTS, ESP_HIDH_INPUT_EVENT, &p, sizeof(esp_hidh_event_data_t), portMAX_DELAY);
+ return ;
+ }
+
report = esp_hidh_dev_get_input_report_by_id_and_proto(dev, p_rpt[0], mode ? ESP_HID_PROTOCOL_MODE_BOOT : ESP_HID_PROTOCOL_MODE_REPORT);
if (report == NULL) {
ESP_LOGE(TAG, "Report Not Found: %d mode: %s", p_rpt[0], mode ? "BOOT" : "REPORT");
@@ -673,7 +673,7 @@ static void esp_hh_cb(esp_hidh_cb_event_t event, esp_hidh_cb_param_t *param)
if (param->data_ind.len == 9 && *(param->data_ind.data) == 1) {
has_report_id = true;
_usage = ESP_HID_USAGE_KEYBOARD;
- } else if (param->data_ind.len == 4 && *(param->data_ind.data) == 2) {
+ } else if (param->data_ind.len >= 4 && *(param->data_ind.data) == 2) {
has_report_id = true;
_usage = ESP_HID_USAGE_MOUSE;
} else {

View File

@ -24,12 +24,13 @@
#include "sdkconfig.h"
#include "freertos/FreeRTOS.h"
#include "freertos/queue.h"
#include "freertos/semphr.h"
#include "freertos/task.h"
#include "esp_log.h"
#include "esp_system.h"
#include "esp_spi_flash.h"
#include "esp_chip_info.h"
#include "esp_private/periph_ctrl.h"
#include "driver/rmt.h"
#include "driver/periph_ctrl.h"
#include "soc/periph_defs.h"
#include "soc/rmt_reg.h"
@ -402,9 +403,9 @@ static inline void adb_rx_setup() {
static inline void adb_tx_as() {
/* send attention (800 µs low) + sync (70 µs high) */
gpio_set_level(GPIO_ADB, 0);
ets_delay_us(800-1);
esp_rom_delay_us(800-1);
gpio_set_level(GPIO_ADB, 1);
ets_delay_us(70-1);
esp_rom_delay_us(70-1);
}
void IRAM_ATTR adb_tx_cmd(unsigned char cmd) {
@ -458,16 +459,16 @@ void adb_tx_listen(unsigned char cmd, uint16_t data) {
adb_tx_cmd(cmd);
/* Stop to start is between 160-240µS. Go for around 160 + time for GPIO setup */
ets_delay_us(160);
esp_rom_delay_us(160);
adb_tx_data(data);
}
static inline void adb_tx_one() {
/* values from AN591 Datasheet minus the estimated call to ets_delay_us */
/* values from AN591 Datasheet minus the estimated call to esp_rom_delay_us */
gpio_set_level(GPIO_ADB, 0);
ets_delay_us(ADB_1_LOW - 1);
esp_rom_delay_us(ADB_1_LOW - 1);
gpio_set_level(GPIO_ADB, 1);
ets_delay_us(ADB_1_HIGH - 1);
esp_rom_delay_us(ADB_1_HIGH - 1);
}
void adb_tx_reset() {
@ -478,9 +479,9 @@ void adb_tx_reset() {
*/
gpio_set_level(GPIO_ADB, 0);
ets_delay_us(ADB_RESET);
esp_rom_delay_us(ADB_RESET);
gpio_set_level(GPIO_ADB, 1);
ets_delay_us(500);
esp_rom_delay_us(500);
}
static inline void adb_tx_setup() {
@ -489,9 +490,9 @@ static inline void adb_tx_setup() {
}
static inline void adb_tx_zero() {
/* values from AN591 Datasheet minus the estimated call to ets_delay_us */
/* values from AN591 Datasheet minus the estimated call to esp_rom_delay_us */
gpio_set_level(GPIO_ADB, 0);
ets_delay_us(ADB_0_LOW - 1);
esp_rom_delay_us(ADB_0_LOW - 1);
gpio_set_level(GPIO_ADB, 1);
ets_delay_us(ADB_0_HIGH - 1);
esp_rom_delay_us(ADB_0_HIGH - 1);
}

View File

@ -25,6 +25,7 @@
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#include "freertos/event_groups.h"
#include "esp_system.h"
#include "esp_wifi.h"
@ -38,7 +39,9 @@
#include "esp_gatt_defs.h"
#include "esp_bt_main.h"
#include "esp_bt_device.h"
#include "esp_timer.h"
#include "esp_hid_common.h"
#include "esp_hidd.h"
#include "esp_hidh.h"
#include "esp_hid_gap.h"
@ -170,7 +173,7 @@ void blue_adb2hid(void *pvParameters) {
uint16_t data = 0;
uint8_t buffer[3] = {0, 0, 0};
int8_t move = 0;
unsigned int tmp;
long unsigned int tmp;
ESP_LOGD(TAG, "ADB2BT started on core %d", xPortGetCoreID());
@ -373,6 +376,7 @@ void blue_h_input(esp_hidh_dev_t *dev, uint8_t *data, uint16_t length) {
uint8_t i;
int8_t x, y;
//ESP_LOG_BUFFER_HEX(TAG, data, length);
buttons = data[0];
/*
@ -580,56 +584,8 @@ void blue_scan(void *pvParameters) {
void blue_set_boot_protocol(esp_hidh_dev_t *dev) {
configASSERT(dev != NULL);
/*
* /!\ Disclaimer /!\
* This is ugly. We are accessing directly bluedroid and need the hidden handle to do that
* Extract it from a private esp_hidh_dev_s struct and call BTA_HhSetProtoMode directly.
*/
struct decoy_dev_s {
struct esp_hidh_dev_s *next;
esp_hid_device_config_t config;
esp_hid_usage_t usage;
esp_hid_transport_t transport;
bool connected;
bool opened;
int status;
size_t reports_len;
void *reports;
void *tmp;
size_t tmp_len;
xSemaphoreHandle semaphore;
esp_err_t (*close) (esp_hidh_dev_t *dev);
esp_err_t (*report_write) (esp_hidh_dev_t *dev, size_t map_index, size_t report_id, int report_type, uint8_t *data, size_t len);
esp_err_t (*report_read) (esp_hidh_dev_t *dev, size_t map_index, size_t report_id, int report_type, size_t max_length, uint8_t *value, size_t *value_len);
void (*dump) (esp_hidh_dev_t *dev, FILE *fp);
esp_bd_addr_t bda;
struct {
esp_bt_cod_t cod;
int handle;
uint8_t sub_class;
uint8_t app_id;
uint16_t attr_mask;
} bt;
TAILQ_ENTRY(esp_hidh_dev_s) devices;
};
struct decoy_dev_s *pass_that_handle;
pass_that_handle = (struct decoy_dev_s *)dev;
ESP_LOGI(TAG, "switching " ESP_BD_ADDR_STR " (%i) to protocol mode boot" ,
ESP_BD_ADDR_HEX(pass_that_handle->bda), pass_that_handle->bt.handle);
//ESP_LOG_BUFFER_HEX(TAG, dev, sizeof(struct decoy_dev_s));
/* bluedroid/bta/include/bta_hh_api.h */
BTA_HhSetProtoMode(pass_that_handle->bt.handle, 0x01);
ESP_LOGI(TAG, "switching " ESP_BD_ADDR_STR " to protocol mode boot", ESP_BD_ADDR_HEX(esp_hidh_dev_bda_get(dev)));
esp_hidh_dev_set_protocol(dev, ESP_HID_PROTOCOL_MODE_BOOT);
}
static bool blue_support_boot(esp_hidh_dev_t *dev) {

View File

@ -1,19 +1,13 @@
// Copyright 2017-2019 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
/*
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Unlicense OR CC0-1.0
*/
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <string.h>
#include <stdbool.h>
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
@ -24,8 +18,11 @@
static const char *TAG = "ESP_HID_GAP";
// uncomment to print all devices that were seen during a scan
#define GAP_DBG_PRINTF(...) //printf(__VA_ARGS__)
//static const char * gap_bt_prop_type_names[5] = {"","BDNAME","COD","RSSI","EIR"};
#define GAP_DBG_PRINTF(...) printf(__VA_ARGS__)
#if CONFIG_BT_HID_HOST_ENABLED
static const char * gap_bt_prop_type_names[5] = {"","BDNAME","COD","RSSI","EIR"};
#endif
static esp_hid_scan_result_t *bt_scan_results = NULL;
static size_t num_bt_scan_results = 0;
@ -33,11 +30,11 @@ static size_t num_bt_scan_results = 0;
static esp_hid_scan_result_t *ble_scan_results = NULL;
static size_t num_ble_scan_results = 0;
static xSemaphoreHandle bt_hidh_cb_semaphore = NULL;
static SemaphoreHandle_t bt_hidh_cb_semaphore = NULL;
#define WAIT_BT_CB() xSemaphoreTake(bt_hidh_cb_semaphore, portMAX_DELAY)
#define SEND_BT_CB() xSemaphoreGive(bt_hidh_cb_semaphore)
static xSemaphoreHandle ble_hidh_cb_semaphore = NULL;
static SemaphoreHandle_t ble_hidh_cb_semaphore = NULL;
#define WAIT_BLE_CB() xSemaphoreTake(ble_hidh_cb_semaphore, portMAX_DELAY)
#define SEND_BLE_CB() xSemaphoreGive(ble_hidh_cb_semaphore)
@ -71,6 +68,7 @@ const char *bt_gap_evt_str(uint8_t event)
return bt_gap_evt_names[event];
}
#if CONFIG_BT_BLE_ENABLED
const char *esp_ble_key_type_str(esp_ble_key_type_t key_type)
{
const char *key_str = NULL;
@ -109,6 +107,7 @@ const char *esp_ble_key_type_str(esp_ble_key_type_t key_type)
}
return key_str;
}
#endif /* CONFIG_BT_BLE_ENABLED */
void esp_hid_scan_results_free(esp_hid_scan_result_t *results)
{
@ -123,6 +122,7 @@ void esp_hid_scan_results_free(esp_hid_scan_result_t *results)
}
}
#if (CONFIG_BT_HID_HOST_ENABLED || CONFIG_BT_BLE_ENABLED)
static esp_hid_scan_result_t *find_scan_result(esp_bd_addr_t bda, esp_hid_scan_result_t *results)
{
esp_hid_scan_result_t *r = results;
@ -134,7 +134,9 @@ static esp_hid_scan_result_t *find_scan_result(esp_bd_addr_t bda, esp_hid_scan_r
}
return NULL;
}
#endif /* (CONFIG_BT_HID_HOST_ENABLED || CONFIG_BT_BLE_ENABLED) */
#if CONFIG_BT_HID_HOST_ENABLED
static void add_bt_scan_result(esp_bd_addr_t bda, esp_bt_cod_t *cod, esp_bt_uuid_t *uuid, uint8_t *name, uint8_t name_len, int rssi)
{
esp_hid_scan_result_t *r = find_scan_result(bda, bt_scan_results);
@ -186,7 +188,9 @@ static void add_bt_scan_result(esp_bd_addr_t bda, esp_bt_cod_t *cod, esp_bt_uuid
bt_scan_results = r;
num_bt_scan_results++;
}
#endif
#if CONFIG_BT_BLE_ENABLED
static void add_ble_scan_result(esp_bd_addr_t bda, esp_ble_addr_type_t addr_type, uint16_t appearance, uint8_t *name, uint8_t name_len, int rssi)
{
if (find_scan_result(bda, ble_scan_results)) {
@ -220,13 +224,14 @@ static void add_ble_scan_result(esp_bd_addr_t bda, esp_ble_addr_type_t addr_type
ble_scan_results = r;
num_ble_scan_results++;
}
#endif /* CONFIG_BT_BLE_ENABLED */
void print_uuid(esp_bt_uuid_t *uuid)
{
if (uuid->len == ESP_UUID_LEN_16) {
GAP_DBG_PRINTF("UUID16: 0x%04x", uuid->uuid.uuid16);
} else if (uuid->len == ESP_UUID_LEN_32) {
GAP_DBG_PRINTF("UUID32: 0x%08x", uuid->uuid.uuid32);
GAP_DBG_PRINTF("UUID32: 0x%08"PRIx32, uuid->uuid.uuid32);
} else if (uuid->len == ESP_UUID_LEN_128) {
GAP_DBG_PRINTF("UUID128: %02x,%02x,%02x,%02x,%02x,%02x,%02x,%02x,%02x,%02x,%02x,%02x,%02x,%02x,%02x,%02x", uuid->uuid.uuid128[0],
uuid->uuid.uuid128[1], uuid->uuid.uuid128[2], uuid->uuid.uuid128[3],
@ -237,6 +242,7 @@ void print_uuid(esp_bt_uuid_t *uuid)
}
}
#if CONFIG_BT_HID_HOST_ENABLED
static void handle_bt_device_result(struct disc_res_param *disc_res)
{
GAP_DBG_PRINTF("BT : " ESP_BD_ADDR_STR, ESP_BD_ADDR_HEX(disc_res->bda));
@ -325,7 +331,9 @@ static void handle_bt_device_result(struct disc_res_param *disc_res)
add_bt_scan_result(disc_res->bda, cod, &uuid, name, name_len, rssi);
}
}
#endif
#if CONFIG_BT_BLE_ENABLED
static void handle_ble_device_result(struct ble_scan_result_evt_param *scan_rst)
{
@ -371,8 +379,9 @@ static void handle_ble_device_result(struct ble_scan_result_evt_param *scan_rst)
add_ble_scan_result(scan_rst->bda, scan_rst->ble_addr_type, appearance, adv_name, adv_name_len, scan_rst->rssi);
}
}
#endif /* CONFIG_BT_BLE_ENABLED */
#if CONFIG_BT_HID_HOST_ENABLED
/*
* BT GAP
* */
@ -392,10 +401,10 @@ static void bt_gap_event_handler(esp_bt_gap_cb_event_t event, esp_bt_gap_cb_para
break;
}
case ESP_BT_GAP_KEY_NOTIF_EVT:
ESP_LOGI(TAG, "BT GAP KEY_NOTIF passkey:%d", param->key_notif.passkey);
ESP_LOGI(TAG, "BT GAP KEY_NOTIF passkey:%"PRIu32, param->key_notif.passkey);
break;
default:
ESP_LOGV(TAG, "BT GAP EVENT %s", bt_gap_evt_str(event));
ESP_LOGW(TAG, "BT GAP EVENT %s", bt_gap_evt_str(event));
break;
}
}
@ -403,9 +412,12 @@ static void bt_gap_event_handler(esp_bt_gap_cb_event_t event, esp_bt_gap_cb_para
static esp_err_t init_bt_gap(void)
{
esp_err_t ret;
#if (CONFIG_BT_SSP_ENABLED)
/* Set default parameters for Secure Simple Pairing */
esp_bt_sp_param_t param_type = ESP_BT_SP_IOCAP_MODE;
esp_bt_io_cap_t iocap = ESP_BT_IO_CAP_IO;
esp_bt_gap_set_security_param(param_type, &iocap, sizeof(uint8_t));
#endif
/*
* Set default parameters for Legacy Pairing
* Use fixed pin code
@ -440,7 +452,9 @@ static esp_err_t start_bt_scan(uint32_t seconds)
}
return ret;
}
#endif
#if CONFIG_BT_BLE_ENABLED
/*
* BLE GAP
* */
@ -506,13 +520,13 @@ static void ble_gap_event_handler(esp_gap_ble_cb_event_t event, esp_ble_gap_cb_p
case ESP_GAP_BLE_PASSKEY_NOTIF_EVT: // ESP_IO_CAP_OUT
// The app will receive this evt when the IO has Output capability and the peer device IO has Input capability.
// Show the passkey number to the user to input it in the peer device.
ESP_LOGI(TAG, "BLE GAP PASSKEY_NOTIF passkey:%d", param->ble_security.key_notif.passkey);
ESP_LOGI(TAG, "BLE GAP PASSKEY_NOTIF passkey:%"PRIu32, param->ble_security.key_notif.passkey);
break;
case ESP_GAP_BLE_NC_REQ_EVT: // ESP_IO_CAP_IO
// The app will receive this event when the IO has DisplayYesNO capability and the peer device IO also has DisplayYesNo capability.
// show the passkey number to the user to confirm it with the number displayed by peer device.
ESP_LOGI(TAG, "BLE GAP NC_REQ passkey:%d", param->ble_security.key_notif.passkey);
ESP_LOGI(TAG, "BLE GAP NC_REQ passkey:%"PRIu32, param->ble_security.key_notif.passkey);
esp_ble_confirm_reply(param->ble_security.key_notif.bd_addr, true);
break;
@ -662,6 +676,7 @@ esp_err_t esp_hid_ble_gap_adv_start(void)
};
return esp_ble_gap_start_advertising(&hidd_adv_params);
}
#endif /* CONFIG_BT_BLE_ENABLED */
/*
* CONTROLLER INIT
@ -671,11 +686,16 @@ static esp_err_t init_low_level(uint8_t mode)
{
esp_err_t ret;
esp_bt_controller_config_t bt_cfg = BT_CONTROLLER_INIT_CONFIG_DEFAULT();
#if CONFIG_IDF_TARGET_ESP32
bt_cfg.mode = mode;
#endif
#if CONFIG_BT_HID_HOST_ENABLED
if (mode & ESP_BT_MODE_CLASSIC_BT) {
bt_cfg.mode = mode;
bt_cfg.bt_max_acl_conn = 3;
bt_cfg.bt_max_sync_conn = 3;
} else {
} else
#endif
{
ret = esp_bt_controller_mem_release(ESP_BT_MODE_CLASSIC_BT);
if (ret) {
ESP_LOGE(TAG, "esp_bt_controller_mem_release failed: %d", ret);
@ -705,26 +725,25 @@ static esp_err_t init_low_level(uint8_t mode)
ESP_LOGE(TAG, "esp_bluedroid_enable failed: %d", ret);
return ret;
}
#if CONFIG_BT_HID_HOST_ENABLED
if (mode & ESP_BT_MODE_CLASSIC_BT) {
ret = init_bt_gap();
if (ret) {
return ret;
}
}
#endif
#if CONFIG_BT_BLE_ENABLED
if (mode & ESP_BT_MODE_BLE) {
ret = init_ble_gap();
if (ret) {
return ret;
}
}
#endif /* CONFIG_BT_BLE_ENABLED */
return ret;
}
esp_err_t esp_hid_gap_init(uint8_t mode)
{
esp_err_t ret;
@ -771,14 +790,21 @@ esp_err_t esp_hid_scan(uint32_t seconds, size_t *num_results, esp_hid_scan_resul
return ESP_FAIL;
}
#if CONFIG_BT_BLE_ENABLED
if (start_ble_scan(seconds) == ESP_OK) {
if (start_bt_scan(seconds) == ESP_OK) {
WAIT_BT_CB();
}
WAIT_BLE_CB();
} else {
return ESP_FAIL;
}
#endif /* CONFIG_BT_BLE_ENABLED */
#if CONFIG_BT_HID_HOST_ENABLED
if (start_bt_scan(seconds) == ESP_OK) {
WAIT_BT_CB();
} else {
return ESP_FAIL;
}
#endif
*num_results = num_bt_scan_results + num_ble_scan_results;
*results = bt_scan_results;

View File

@ -25,7 +25,6 @@
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "esp_system.h"
#include "esp_spi_flash.h"
#include "gpio.h"

View File

@ -27,7 +27,6 @@
#include "freertos/task.h"
#include "esp_log.h"
#include "esp_system.h"
#include "esp_spi_flash.h"
#include "led.h"
#include "gpio.h"
@ -164,7 +163,7 @@ const char *led_gpio_name(uint8_t id) {
}
void led_init(void) {
/* blink allds LEDs once */
/* blink alls LEDs once */
gpio_set_level(GPIO_GREENLED, 1);
gpio_set_level(GPIO_BLUELED, 1);
gpio_set_level(GPIO_YELLOWLED, 1);
@ -185,7 +184,7 @@ void led_init(void) {
void led_task(void *pvParameters) {
unsigned int color = (unsigned int)pvParameters;
unsigned int mode = LED_OFF;
long unsigned int mode = LED_OFF;
TickType_t wait = portMAX_DELAY;
/* start only if there is a led specified */

View File

@ -24,10 +24,11 @@
#include "sdkconfig.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "esp_flash.h"
#include "esp_hidh.h"
#include "esp_log.h"
#include "esp_system.h"
#include "esp_spi_flash.h"
#include "esp_chip_info.h"
#include "adb.h"
#include "blue.h"
@ -40,20 +41,22 @@ static const char* TAG = "quack";
void app_main(void)
{
uint32_t flash_size;
esp_flash_get_size(NULL, &flash_size);
/* Print chip information */
esp_chip_info_t chip_info;
esp_chip_info(&chip_info);
ESP_LOGI(TAG, "This is %s chip with %d CPU cores, WiFi%s%s, "
"revision %d, %dMB %s flash",
"revision %d, %" PRIu32 "MB %s flash",
CONFIG_IDF_TARGET,
chip_info.cores,
(chip_info.features & CHIP_FEATURE_BT) ? "/BT" : "",
(chip_info.features & CHIP_FEATURE_BLE) ? "/BLE" : "",
chip_info.revision,
spi_flash_get_chip_size() / (1024 * 1024),
chip_info.revision, flash_size / (1024 * 1024),
(chip_info.features & CHIP_FEATURE_EMB_FLASH) ? "embedded" : "external");
ESP_LOGI(TAG, "Minimum free heap size: %d bytes", esp_get_minimum_free_heap_size());
ESP_LOGI(TAG, "Minimum free heap size: %" PRIu32 " bytes", esp_get_minimum_free_heap_size());
ESP_LOGI(TAG, "");
ESP_LOGI(TAG, "\\_o< \\_o< \\_o< \\_O<");
ESP_LOGI(TAG, "");

View File

@ -28,7 +28,6 @@
#include "esp_system.h"
#include "esp_err.h"
#include "esp_log.h"
#include "driver/timer.h"
#include "esp_timer.h"
#include "quad.h"
@ -40,8 +39,8 @@ esp_timer_handle_t quad_qx, quad_qy;
QueueHandle_t q_qx, q_qy;
/* static functions */
static void IRAM_ATTR quad_timer(void* arg);
/* ISR functions */
static void IRAM_ATTR quad_isr(void* arg);
/* phases */
const bool q1[] = {true, false, false, true};
@ -51,6 +50,10 @@ const bool q2[] = {true, true, false, false};
void quad_init(void) {
esp_timer_create_args_t args;
/* create quadrature queues */
q_qx = xQueueCreate(4, sizeof(int8_t));
q_qy = xQueueCreate(4, sizeof(int8_t));
/* create quadrature tasks */
xTaskCreate(quad_click, "CLICK", 1024, NULL, tskIDLE_PRIORITY + 1, &t_click);
xTaskCreate(quad_move_x, "QX", 4 * 1024, NULL, tskIDLE_PRIORITY + 1, &t_qx);
@ -66,23 +69,23 @@ void quad_init(void) {
gpio_set_level(GPIO_QY2, q2[0]);
/* create timers for quadrature phases */
args.callback = quad_timer;
args.callback = quad_isr;
args.arg = t_qx;
args.name = "quad_qx";
args.dispatch_method = ESP_TIMER_ISR;
ESP_ERROR_CHECK(esp_timer_create(&args, &quad_qx));
args.callback = quad_timer;
args.callback = quad_isr;
args.arg = t_qy;
args.name = "quad_qy";
args.dispatch_method = ESP_TIMER_ISR;
ESP_ERROR_CHECK(esp_timer_create(&args, &quad_qy));
q_qx = xQueueCreate(4, sizeof(int8_t));
q_qy = xQueueCreate(4, sizeof(int8_t));
ESP_LOGI("quad", "Quadrature tasks started on core %d", xPortGetCoreID());
}
void quad_click(void *pvParameters) {
unsigned int click = 0;
long unsigned int click = 0;
(void)pvParameters;
@ -165,7 +168,7 @@ void IRAM_ATTR quad_move_y(void *pvParameters) {
}
/* simple ISR function. Resume the task that called the oneshot timer */
static void IRAM_ATTR quad_timer(void* arg) {
static void IRAM_ATTR quad_isr(void* arg) {
BaseType_t pxHigherPriorityTaskWoken = pdFALSE;
vTaskNotifyGiveFromISR(arg, &pxHigherPriorityTaskWoken);

1501
sdkconfig

File diff suppressed because it is too large Load Diff