HAL to LL migration: GPIO, HSEM, AES (#1069)

* gpio, hsem, crypto: switch from HAL to LL/registers
* Moved GPIO initialization to furi_hal
* More HAL removed
* All HAL modules disabled
* HAL is finally removed
* hal_gpio -> furi_hal_gpio, main.h removed
* Bootloader build fix
* RTOS config moved to freertos-glue
* delay -> furi_hal_delay

Co-authored-by: あく <alleteam@gmail.com>
This commit is contained in:
Nikolay Minaylov
2022-03-30 18:23:40 +03:00
committed by GitHub
parent 648d8aaa54
commit 2f3ea9494e
93 changed files with 921 additions and 1270 deletions

View File

@@ -0,0 +1,138 @@
#pragma once
#if defined(__ICCARM__) || defined(__CC_ARM) || defined(__GNUC__)
#include <stdint.h>
extern uint32_t SystemCoreClock;
#endif
#ifndef CMSIS_device_header
#define CMSIS_device_header "stm32wbxx.h"
#endif /* CMSIS_device_header */
#define configENABLE_FPU 1
#define configENABLE_MPU 0
#define configUSE_PREEMPTION 1
#define configSUPPORT_STATIC_ALLOCATION 0
#define configSUPPORT_DYNAMIC_ALLOCATION 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
#define configCPU_CLOCK_HZ (SystemCoreClock)
#define configTICK_RATE_HZ ((TickType_t)1024)
#define configMAX_PRIORITIES (56)
#define configMINIMAL_STACK_SIZE ((uint16_t)128)
/* Heap size determined automatically by linker */
// #define configTOTAL_HEAP_SIZE ((size_t)0)
#define configMAX_TASK_NAME_LEN (16)
#define configGENERATE_RUN_TIME_STATS 0
#define configUSE_TRACE_FACILITY 1
#define configUSE_16_BIT_TICKS 0
#define configUSE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 8
#define configCHECK_FOR_STACK_OVERFLOW 1
#define configUSE_RECURSIVE_MUTEXES 1
#define configUSE_COUNTING_SEMAPHORES 1
#define configENABLE_BACKWARD_COMPATIBILITY 0
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
#define configUSE_TICKLESS_IDLE 2
#define configRECORD_STACK_HIGH_ADDRESS 1
#define configUSE_NEWLIB_REENTRANT 0
/* Defaults to size_t for backward compatibility, but can be changed
if lengths will always be less than the number of bytes in a size_t. */
#define configMESSAGE_BUFFER_LENGTH_TYPE size_t
#define configNUM_THREAD_LOCAL_STORAGE_POINTERS 1
#define configEXPECTED_IDLE_TIME_BEFORE_SLEEP 4
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
/* Software timer definitions. */
#define configUSE_TIMERS 1
#define configTIMER_TASK_PRIORITY (2)
#define configTIMER_QUEUE_LENGTH 32
#define configTIMER_TASK_STACK_DEPTH 256
#define configTIMER_SERVICE_TASK_NAME "TimersSrv"
#define configIDLE_TASK_NAME "(-_-)"
/* Set the following definitions to 1 to include the API function, or zero
to exclude the API function. */
#define INCLUDE_xTaskGetHandle 1
#define INCLUDE_eTaskGetState 1
#define INCLUDE_uxTaskGetStackHighWaterMark 1
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskCleanUpResources 0
#define INCLUDE_vTaskDelay 1
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_xQueueGetMutexHolder 1
#define INCLUDE_xTaskGetCurrentTaskHandle 1
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_xTimerPendFunctionCall 1
/* CMSIS-RTOS V2 flags */
#define configUSE_OS2_THREAD_SUSPEND_RESUME 1
#define configUSE_OS2_THREAD_ENUMERATE 1
#define configUSE_OS2_EVENTFLAGS_FROM_ISR 1
#define configUSE_OS2_THREAD_FLAGS 1
#define configUSE_OS2_TIMER 1
#define configUSE_OS2_MUTEX 1
/* CMSIS-RTOS */
#define configTASK_NOTIFICATION_ARRAY_ENTRIES 2
#define CMSIS_TASK_NOTIFY_INDEX 1
/*
* The CMSIS-RTOS V2 FreeRTOS wrapper is dependent on the heap implementation used
* by the application thus the correct define need to be enabled below
*/
#define USE_FreeRTOS_HEAP_4
/* Cortex-M specific definitions. */
#ifdef __NVIC_PRIO_BITS
/* __BVIC_PRIO_BITS will be specified when CMSIS is being used. */
#define configPRIO_BITS __NVIC_PRIO_BITS
#else
#define configPRIO_BITS 4
#endif
/* The lowest interrupt priority that can be used in a call to a "set priority"
function. */
#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 15
/* The highest interrupt priority that can be used by any interrupt service
routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL
INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER
PRIORITY THAN THIS! (higher priorities are lower numeric values. */
#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 5
/* Interrupt priorities used by the kernel port layer itself. These are generic
to all Cortex-M ports, and do not rely on any particular library functions. */
#define configKERNEL_INTERRUPT_PRIORITY \
(configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS))
/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
#define configMAX_SYSCALL_INTERRUPT_PRIORITY \
(configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS))
/* Normal assert() semantics without relying on the provision of an assert.h
header file. */
#include <furi/check.h>
#define configASSERT(x) \
if((x) == 0) { \
furi_crash("FreeRTOS Assert"); \
}
/* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS
standard names. */
#define vPortSVCHandler SVC_Handler
#define xPortPendSVHandler PendSV_Handler
#define USE_CUSTOM_SYSTICK_HANDLER_IMPLEMENTATION 1
#define configOVERRIDE_DEFAULT_TICK_CONFIGURATION \
1 /* required only for Keil but does not hurt otherwise */

View File

@@ -1,6 +1,5 @@
#include "platform.h"
#include <assert.h>
#include <main.h>
#include <furi.h>
#include <furi_hal_spi.h>
@@ -30,25 +29,25 @@ void platformIrqThread() {
}
void platformEnableIrqCallback() {
hal_gpio_init(&pin, GpioModeInterruptRise, GpioPullDown, GpioSpeedLow);
hal_gpio_enable_int_callback(&pin);
furi_hal_gpio_init(&pin, GpioModeInterruptRise, GpioPullDown, GpioSpeedLow);
furi_hal_gpio_enable_int_callback(&pin);
}
void platformDisableIrqCallback() {
hal_gpio_init(&pin, GpioModeOutputOpenDrain, GpioPullNo, GpioSpeedLow);
hal_gpio_disable_int_callback(&pin);
furi_hal_gpio_init(&pin, GpioModeOutputOpenDrain, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_disable_int_callback(&pin);
}
void platformSetIrqCallback(PlatformIrqCallback callback) {
platform_irq_callback = callback;
platform_irq_thread_id = osThreadNew(platformIrqThread, NULL, &platform_irq_thread_attr);
hal_gpio_add_int_callback(&pin, nfc_isr, NULL);
furi_hal_gpio_add_int_callback(&pin, nfc_isr, NULL);
// Disable interrupt callback as the pin is shared between 2 apps
// It is enabled in rfalLowPowerModeStop()
hal_gpio_disable_int_callback(&pin);
furi_hal_gpio_disable_int_callback(&pin);
}
HAL_StatusTypeDef platformSpiTxRx(const uint8_t* txBuf, uint8_t* rxBuf, uint16_t len) {
bool platformSpiTxRx(const uint8_t* txBuf, uint8_t* rxBuf, uint16_t len) {
bool ret = false;
if(txBuf && rxBuf) {
ret =
@@ -59,11 +58,7 @@ HAL_StatusTypeDef platformSpiTxRx(const uint8_t* txBuf, uint8_t* rxBuf, uint16_t
ret = furi_hal_spi_bus_rx(&furi_hal_spi_bus_handle_nfc, (uint8_t*)rxBuf, len, 1000);
}
if(!ret) {
return HAL_ERROR;
} else {
return HAL_OK;
}
return ret;
}
void platformProtectST25RComm() {

View File

@@ -5,10 +5,8 @@
#include <stdbool.h>
#include <limits.h>
#include <cmsis_os2.h>
#include <gpio.h>
#include "timer.h"
#include "math.h"
#include "main.h"
#include <furi_hal_gpio.h>
#include <furi_hal_light.h>
#include <furi_hal_spi.h>
@@ -18,7 +16,7 @@ void platformSetIrqCallback(PlatformIrqCallback cb);
void platformEnableIrqCallback();
void platformDisableIrqCallback();
HAL_StatusTypeDef platformSpiTxRx(const uint8_t* txBuf, uint8_t* rxBuf, uint16_t len);
bool platformSpiTxRx(const uint8_t* txBuf, uint8_t* rxBuf, uint16_t len);
void platformProtectST25RComm();
void platformUnprotectST25RComm();
@@ -87,11 +85,18 @@ void platformUnprotectST25RComm();
#define platformUnprotectST25RIrqStatus() \
platformUnprotectST25RComm() /*!< Unprotect the IRQ status var - IRQ enable on a single thread environment (MCU) ; Mutex unlock on a multi thread environment */
#define platformGpioSet(port, pin) LL_GPIO_SetOutputPin(port, pin)
#define platformGpioSet(port, pin) \
furi_hal_gpio_write_port_pin( \
port, pin, true) /*!< Turns the given GPIO High */
#define platformGpioClear(port, pin) \
furi_hal_gpio_write_port_pin( \
port, pin, false) /*!< Turns the given GPIO Low */
#define platformGpioClear(port, pin) LL_GPIO_ResetOutputPin(port, pin)
#define platformGpioIsHigh(port, pin) LL_GPIO_IsInputPinSet(port, pin)
#define platformGpioIsHigh(port, pin) \
(furi_hal_gpio_read_port_pin(port, pin) == \
true) /*!< Checks if the given LED is High */
#define platformGpioIsLow(port, pin) \
(!platformGpioIsHigh(port, pin)) /*!< Checks if the given LED is Low */
#define platformTimerCreate(t) \
timerCalculateTimer(t) /*!< Create a timer with the given time (ms) */

View File

@@ -41,6 +41,7 @@
******************************************************************************
*/
#include "timer.h"
#include <furi_hal_delay.h>
/*
******************************************************************************
@@ -64,7 +65,7 @@ static uint32_t timerStopwatchTick;
/*******************************************************************************/
uint32_t timerCalculateTimer(uint16_t time) {
return (HAL_GetTick() + time);
return (furi_hal_get_tick() + time);
}
/*******************************************************************************/
@@ -72,7 +73,7 @@ bool timerIsExpired(uint32_t timer) {
uint32_t uDiff;
int32_t sDiff;
uDiff = (timer - HAL_GetTick()); /* Calculate the diff between the timers */
uDiff = (timer - furi_hal_get_tick()); /* Calculate the diff between the timers */
sDiff = uDiff; /* Convert the diff to a signed var */
/* Check if the given timer has expired already */
@@ -95,10 +96,10 @@ void timerDelay(uint16_t tOut) {
/*******************************************************************************/
void timerStopwatchStart(void) {
timerStopwatchTick = HAL_GetTick();
timerStopwatchTick = furi_hal_get_tick();
}
/*******************************************************************************/
uint32_t timerStopwatchMeasure(void) {
return (uint32_t)(HAL_GetTick() - timerStopwatchTick);
return (uint32_t)(furi_hal_get_tick() - timerStopwatchTick);
}

View File

@@ -42,7 +42,7 @@ bool bq27220_set_parameter_u16(FuriHalI2cBusHandle* handle, uint16_t address, ui
ret = furi_hal_i2c_write_mem(
handle, BQ27220_ADDRESS, CommandSelectSubclass, buffer, 4, BQ27220_I2C_TIMEOUT);
delay_us(10000);
furi_hal_delay_us(10000);
uint8_t checksum = bq27220_get_checksum(buffer, 4);
buffer[0] = checksum;
@@ -50,7 +50,7 @@ bool bq27220_set_parameter_u16(FuriHalI2cBusHandle* handle, uint16_t address, ui
ret = furi_hal_i2c_write_mem(
handle, BQ27220_ADDRESS, CommandMACDataSum, buffer, 2, BQ27220_I2C_TIMEOUT);
delay_us(10000);
furi_hal_delay_us(10000);
return ret;
}
@@ -96,7 +96,7 @@ bool bq27220_init(FuriHalI2cBusHandle* handle, const ParamCEDV* cedv) {
bq27220_set_parameter_u16(handle, AddressEDV2, cedv->EDV2);
bq27220_control(handle, Control_EXIT_CFG_UPDATE_REINIT);
delay_us(10000);
furi_hal_delay_us(10000);
design_cap = bq27220_get_design_capacity(handle);
if(cedv->design_cap == design_cap) {
FURI_LOG_I(TAG, "Battery profile update success");

View File

@@ -8,7 +8,7 @@ CC1101Status cc1101_strobe(FuriHalSpiBusHandle* handle, uint8_t strobe) {
uint8_t tx[1] = {strobe};
CC1101Status rx[1] = {0};
while(hal_gpio_read(handle->miso))
while(furi_hal_gpio_read(handle->miso))
;
furi_hal_spi_bus_trx(handle, tx, (uint8_t*)rx, 1, CC1101_TIMEOUT);
@@ -20,7 +20,7 @@ CC1101Status cc1101_write_reg(FuriHalSpiBusHandle* handle, uint8_t reg, uint8_t
uint8_t tx[2] = {reg, data};
CC1101Status rx[2] = {0};
while(hal_gpio_read(handle->miso))
while(furi_hal_gpio_read(handle->miso))
;
furi_hal_spi_bus_trx(handle, tx, (uint8_t*)rx, 2, CC1101_TIMEOUT);
@@ -33,7 +33,7 @@ CC1101Status cc1101_read_reg(FuriHalSpiBusHandle* handle, uint8_t reg, uint8_t*
uint8_t tx[2] = {reg | CC1101_READ, 0};
CC1101Status rx[2] = {0};
while(hal_gpio_read(handle->miso))
while(furi_hal_gpio_read(handle->miso))
;
furi_hal_spi_bus_trx(handle, tx, (uint8_t*)rx, 2, CC1101_TIMEOUT);
@@ -128,7 +128,7 @@ void cc1101_set_pa_table(FuriHalSpiBusHandle* handle, const uint8_t value[8]) {
memcpy(&tx[1], &value[0], 8);
while(hal_gpio_read(handle->miso))
while(furi_hal_gpio_read(handle->miso))
;
furi_hal_spi_bus_trx(handle, tx, (uint8_t*)rx, sizeof(rx), CC1101_TIMEOUT);
@@ -143,7 +143,7 @@ uint8_t cc1101_write_fifo(FuriHalSpiBusHandle* handle, const uint8_t* data, uint
// Start transaction
// Wait IC to become ready
while(hal_gpio_read(handle->miso))
while(furi_hal_gpio_read(handle->miso))
;
// Tell IC what we want
furi_hal_spi_bus_trx(handle, buff_tx, (uint8_t*)buff_rx, size + 1, CC1101_TIMEOUT);
@@ -158,7 +158,7 @@ uint8_t cc1101_read_fifo(FuriHalSpiBusHandle* handle, uint8_t* data, uint8_t* si
// Start transaction
// Wait IC to become ready
while(hal_gpio_read(handle->miso))
while(furi_hal_gpio_read(handle->miso))
;
// First byte - packet length

View File

@@ -26,7 +26,7 @@ void lp5562_enable(FuriHalI2cBusHandle* handle) {
Reg00_Enable reg = {.CHIP_EN = true, .LOG_EN = true};
furi_hal_i2c_write_reg_8(handle, LP5562_ADDRESS, 0x00, *(uint8_t*)&reg, LP5562_I2C_TIMEOUT);
//>488μs delay is required after writing to 0x00 register, otherwise program engine will not work
delay_us(500);
furi_hal_delay_us(500);
}
void lp5562_set_channel_current(FuriHalI2cBusHandle* handle, LP5562Channel channel, uint8_t value) {
@@ -121,7 +121,7 @@ void lp5562_execute_program(
reg_val &= ~(0x3 << bit_offset);
reg_val |= (0x01 << bit_offset); // load
furi_hal_i2c_write_reg_8(handle, LP5562_ADDRESS, 0x01, reg_val, LP5562_I2C_TIMEOUT);
delay_us(100);
furi_hal_delay_us(100);
// Program load
for(uint8_t i = 0; i < 16; i++) {

View File

@@ -83,7 +83,7 @@ bool ibutton_worker_read_comparator(iButtonWorker* worker) {
furi_hal_rfid_comp_start();
// TODO: rework with thread events, "pulse_decoder_get_decoded_index_with_timeout"
delay(100);
furi_hal_delay_ms(100);
int32_t decoded_index = pulse_decoder_get_decoded_index(worker->pulse_decoder);
if(decoded_index >= 0) {
pulse_decoder_get_data(
@@ -118,7 +118,7 @@ bool ibutton_worker_read_comparator(iButtonWorker* worker) {
bool ibutton_worker_read_dallas(iButtonWorker* worker) {
bool result = false;
onewire_host_start(worker->host);
delay(100);
furi_hal_delay_ms(100);
FURI_CRITICAL_ENTER();
if(onewire_host_search(worker->host, worker->key_data, NORMAL_SEARCH)) {
onewire_host_reset_search(worker->host);

View File

@@ -11,13 +11,13 @@ struct iButtonWriter {
static void writer_write_one_bit(iButtonWriter* writer, bool value, uint32_t delay) {
onewire_host_write_bit(writer->host, value);
delay_us(delay);
furi_hal_delay_us(delay);
}
static void writer_write_byte_ds1990(iButtonWriter* writer, uint8_t data) {
for(uint8_t n_bit = 0; n_bit < 8; n_bit++) {
onewire_host_write_bit(writer->host, data & 1);
delay_us(5000);
furi_hal_delay_us(5000);
data = data >> 1;
}
}
@@ -68,7 +68,7 @@ static bool writer_write_TM2004(iButtonWriter* writer, iButtonKey* key) {
// TODO: check answer CRC
// pulse indicating that data is correct
delay_us(600);
furi_hal_delay_us(600);
writer_write_one_bit(writer, 1, 50000);
// read writed key byte
@@ -104,7 +104,7 @@ static bool writer_write_1990_1(iButtonWriter* writer, iButtonKey* key) {
// unlock
onewire_host_reset(writer->host);
onewire_host_write(writer->host, RW1990_1_CMD_WRITE_RECORD_FLAG);
delay_us(10);
furi_hal_delay_us(10);
writer_write_one_bit(writer, 0, 5000);
// write key
@@ -113,7 +113,7 @@ static bool writer_write_1990_1(iButtonWriter* writer, iButtonKey* key) {
for(uint8_t i = 0; i < ibutton_key_get_data_size(key); i++) {
// inverted key for RW1990.1
writer_write_byte_ds1990(writer, ~ibutton_key_get_data_p(key)[i]);
delay_us(30000);
furi_hal_delay_us(30000);
}
// lock
@@ -139,7 +139,7 @@ static bool writer_write_1990_2(iButtonWriter* writer, iButtonKey* key) {
// unlock
onewire_host_reset(writer->host);
onewire_host_write(writer->host, RW1990_2_CMD_WRITE_RECORD_FLAG);
delay_us(10);
furi_hal_delay_us(10);
writer_write_one_bit(writer, 1, 5000);
// write key
@@ -147,7 +147,7 @@ static bool writer_write_1990_2(iButtonWriter* writer, iButtonKey* key) {
onewire_host_write(writer->host, RW1990_2_CMD_WRITE_ROM);
for(uint8_t i = 0; i < ibutton_key_get_data_size(key); i++) {
writer_write_byte_ds1990(writer, ibutton_key_get_data_p(key)[i]);
delay_us(30000);
furi_hal_delay_us(30000);
}
// lock
@@ -191,7 +191,7 @@ static bool writer_write_TM01(
//} else {
for(uint8_t i = 0; i < key->get_type_data_size(); i++) {
write_byte_ds1990(key->get_data()[i]);
delay_us(10000);
furi_hal_delay_us(10000);
}
//}

View File

@@ -30,23 +30,23 @@ bool onewire_host_reset(OneWireHost* host) {
furi_hal_ibutton_pin_high();
do {
if(--retries == 0) return 0;
delay_us(2);
furi_hal_delay_us(2);
} while(!furi_hal_ibutton_pin_get_level());
// pre delay
delay_us(OWH_RESET_DELAY_PRE);
furi_hal_delay_us(OWH_RESET_DELAY_PRE);
// drive low
furi_hal_ibutton_pin_low();
delay_us(OWH_RESET_DRIVE);
furi_hal_delay_us(OWH_RESET_DRIVE);
// release
furi_hal_ibutton_pin_high();
delay_us(OWH_RESET_RELEASE);
furi_hal_delay_us(OWH_RESET_RELEASE);
// read and post delay
r = !furi_hal_ibutton_pin_get_level();
delay_us(OWH_RESET_DELAY_POST);
furi_hal_delay_us(OWH_RESET_DELAY_POST);
return r;
}
@@ -56,15 +56,15 @@ bool onewire_host_read_bit(OneWireHost* host) {
// drive low
furi_hal_ibutton_pin_low();
delay_us(OWH_READ_DRIVE);
furi_hal_delay_us(OWH_READ_DRIVE);
// release
furi_hal_ibutton_pin_high();
delay_us(OWH_READ_RELEASE);
furi_hal_delay_us(OWH_READ_RELEASE);
// read and post delay
result = furi_hal_ibutton_pin_get_level();
delay_us(OWH_READ_DELAY_POST);
furi_hal_delay_us(OWH_READ_DELAY_POST);
return result;
}
@@ -91,19 +91,19 @@ void onewire_host_write_bit(OneWireHost* host, bool value) {
if(value) {
// drive low
furi_hal_ibutton_pin_low();
delay_us(OWH_WRITE_1_DRIVE);
furi_hal_delay_us(OWH_WRITE_1_DRIVE);
// release
furi_hal_ibutton_pin_high();
delay_us(OWH_WRITE_1_RELEASE);
furi_hal_delay_us(OWH_WRITE_1_RELEASE);
} else {
// drive low
furi_hal_ibutton_pin_low();
delay_us(OWH_WRITE_0_DRIVE);
furi_hal_delay_us(OWH_WRITE_0_DRIVE);
// release
furi_hal_ibutton_pin_high();
delay_us(OWH_WRITE_0_RELEASE);
furi_hal_delay_us(OWH_WRITE_0_RELEASE);
}
}

View File

@@ -59,7 +59,7 @@ bool onewire_slave_show_presence(OneWireSlave* bus) {
// show presence
furi_hal_ibutton_pin_low();
delay_us(OWS_PRESENCE_MIN);
furi_hal_delay_us(OWS_PRESENCE_MIN);
furi_hal_ibutton_pin_high();
// somebody also can show presence
@@ -126,7 +126,7 @@ bool onewire_slave_send_bit(OneWireSlave* bus, bool value) {
}
// hold line for ZERO or ONE time
delay_us(time);
furi_hal_delay_us(time);
furi_hal_ibutton_pin_high();
return true;

View File

@@ -75,8 +75,9 @@ void subghz_encoder_princeton_for_testing_set(
instance->count_key = instance->count_key_package + 3;
if((millis() - instance->time_stop) < instance->timeout) {
instance->time_stop = (instance->timeout - (millis() - instance->time_stop)) * 1000;
if((furi_hal_get_tick() - instance->time_stop) < instance->timeout) {
instance->time_stop =
(instance->timeout - (furi_hal_get_tick() - instance->time_stop)) * 1000;
} else {
instance->time_stop = 0;
}

View File

@@ -71,7 +71,7 @@ bool subghz_tx_rx_worker_rx(SubGhzTxRxWorker* instance, uint8_t* data, uint8_t*
osDelay(1);
}
//waiting for reception to complete
while(hal_gpio_read(&gpio_cc1101_g0)) {
while(furi_hal_gpio_read(&gpio_cc1101_g0)) {
osDelay(1);
if(!--timeout) {
FURI_LOG_W(TAG, "RX cc1101_g0 timeout");
@@ -102,14 +102,14 @@ void subghz_tx_rx_worker_tx(SubGhzTxRxWorker* instance, uint8_t* data, size_t si
furi_hal_subghz_write_packet(data, size);
furi_hal_subghz_tx(); //start send
instance->status = SubGhzTxRxWorkerStatusTx;
while(!hal_gpio_read(&gpio_cc1101_g0)) { // Wait for GDO0 to be set -> sync transmitted
while(!furi_hal_gpio_read(&gpio_cc1101_g0)) { // Wait for GDO0 to be set -> sync transmitted
osDelay(1);
if(!--timeout) {
FURI_LOG_W(TAG, "TX !cc1101_g0 timeout");
break;
}
}
while(hal_gpio_read(&gpio_cc1101_g0)) { // Wait for GDO0 to be cleared -> end of packet
while(furi_hal_gpio_read(&gpio_cc1101_g0)) { // Wait for GDO0 to be cleared -> end of packet
osDelay(1);
if(!--timeout) {
FURI_LOG_W(TAG, "TX cc1101_g0 timeout");
@@ -132,7 +132,7 @@ static int32_t subghz_tx_rx_worker_thread(void* context) {
furi_hal_subghz_idle();
furi_hal_subghz_load_preset(FuriHalSubGhzPresetGFSK9_99KbAsync);
//furi_hal_subghz_load_preset(FuriHalSubGhzPresetMSK99_97KbAsync);
hal_gpio_init(&gpio_cc1101_g0, GpioModeInput, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_cc1101_g0, GpioModeInput, GpioPullNo, GpioSpeedLow);
furi_hal_subghz_set_frequency_and_path(instance->frequency);
furi_hal_subghz_flush_rx();

View File

@@ -8,16 +8,16 @@ uint8_t u8g2_gpio_and_delay_stm32(u8x8_t* u8x8, uint8_t msg, uint8_t arg_int, vo
/* HAL initialization contains all what we need so we can skip this part. */
break;
case U8X8_MSG_DELAY_MILLI:
delay(arg_int);
furi_hal_delay_ms(arg_int);
break;
case U8X8_MSG_DELAY_10MICRO:
delay_us(10);
furi_hal_delay_us(10);
break;
case U8X8_MSG_DELAY_100NANO:
asm("nop");
break;
case U8X8_MSG_GPIO_RESET:
hal_gpio_write(&gpio_display_rst, arg_int);
furi_hal_gpio_write(&gpio_display_rst, arg_int);
break;
default:
return 0;
@@ -32,7 +32,7 @@ uint8_t u8x8_hw_spi_stm32(u8x8_t* u8x8, uint8_t msg, uint8_t arg_int, void* arg_
furi_hal_spi_bus_tx(&furi_hal_spi_bus_handle_display, (uint8_t*)arg_ptr, arg_int, 10000);
break;
case U8X8_MSG_BYTE_SET_DC:
hal_gpio_write(&gpio_display_di, arg_int);
furi_hal_gpio_write(&gpio_display_di, arg_int);
break;
case U8X8_MSG_BYTE_INIT:
break;