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

@@ -1,138 +0,0 @@
#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,49 +0,0 @@
/**
******************************************************************************
* @file gpio.h
* @brief This file contains all the function prototypes for
* the gpio.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GPIO_H__
#define __GPIO_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
void MX_GPIO_Init(void);
/* USER CODE BEGIN Prototypes */
/* USER CODE END Prototypes */
#ifdef __cplusplus
}
#endif
#endif /*__ GPIO_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -1,120 +0,0 @@
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32wbxx_hal.h"
#include "stm32wbxx_ll_gpio.h"
void Error_Handler(void);
#define BUTTON_BACK_GPIO_Port GPIOC
#define BUTTON_BACK_Pin LL_GPIO_PIN_13
#define BUTTON_DOWN_GPIO_Port GPIOC
#define BUTTON_DOWN_Pin LL_GPIO_PIN_6
#define BUTTON_LEFT_GPIO_Port GPIOB
#define BUTTON_LEFT_Pin LL_GPIO_PIN_11
#define BUTTON_OK_GPIO_Port GPIOH
#define BUTTON_OK_Pin LL_GPIO_PIN_3
#define BUTTON_RIGHT_GPIO_Port GPIOB
#define BUTTON_RIGHT_Pin LL_GPIO_PIN_12
#define BUTTON_UP_GPIO_Port GPIOB
#define BUTTON_UP_Pin LL_GPIO_PIN_10
#define CC1101_CS_GPIO_Port GPIOD
#define CC1101_CS_Pin LL_GPIO_PIN_0
#define CC1101_G0_GPIO_Port GPIOA
#define CC1101_G0_Pin LL_GPIO_PIN_1
#define DISPLAY_CS_GPIO_Port GPIOC
#define DISPLAY_CS_Pin LL_GPIO_PIN_11
#define DISPLAY_DI_GPIO_Port GPIOB
#define DISPLAY_DI_Pin LL_GPIO_PIN_1
#define DISPLAY_RST_GPIO_Port GPIOB
#define DISPLAY_RST_Pin LL_GPIO_PIN_0
#define IR_RX_GPIO_Port GPIOA
#define IR_RX_Pin LL_GPIO_PIN_0
#define IR_TX_GPIO_Port GPIOB
#define IR_TX_Pin LL_GPIO_PIN_9
#define NFC_CS_GPIO_Port GPIOE
#define NFC_CS_Pin LL_GPIO_PIN_4
#define PA4_GPIO_Port GPIOA
#define PA4_Pin LL_GPIO_PIN_4
#define PA6_GPIO_Port GPIOA
#define PA6_Pin LL_GPIO_PIN_6
#define PA7_GPIO_Port GPIOA
#define PA7_Pin LL_GPIO_PIN_7
#define PB2_GPIO_Port GPIOB
#define PB2_Pin LL_GPIO_PIN_2
#define PB3_GPIO_Port GPIOB
#define PB3_Pin LL_GPIO_PIN_3
#define PC0_GPIO_Port GPIOC
#define PC0_Pin LL_GPIO_PIN_0
#define PC1_GPIO_Port GPIOC
#define PC1_Pin LL_GPIO_PIN_1
#define PC3_GPIO_Port GPIOC
#define PC3_Pin LL_GPIO_PIN_3
#define PERIPH_POWER_GPIO_Port GPIOA
#define PERIPH_POWER_Pin LL_GPIO_PIN_3
#define QUARTZ_32MHZ_IN_GPIO_Port GPIOC
#define QUARTZ_32MHZ_IN_Pin LL_GPIO_PIN_14
#define QUARTZ_32MHZ_OUT_GPIO_Port GPIOC
#define QUARTZ_32MHZ_OUT_Pin LL_GPIO_PIN_15
#define RFID_OUT_GPIO_Port GPIOB
#define RFID_OUT_Pin LL_GPIO_PIN_13
#define RFID_PULL_GPIO_Port GPIOA
#define RFID_PULL_Pin LL_GPIO_PIN_2
#define RFID_RF_IN_GPIO_Port GPIOC
#define RFID_RF_IN_Pin LL_GPIO_PIN_5
#define RFID_CARRIER_GPIO_Port GPIOA
#define RFID_CARRIER_Pin LL_GPIO_PIN_15
#define RF_SW_0_GPIO_Port GPIOC
#define RF_SW_0_Pin LL_GPIO_PIN_4
#define SD_CD_GPIO_Port GPIOC
#define SD_CD_Pin LL_GPIO_PIN_10
#define SD_CS_GPIO_Port GPIOC
#define SD_CS_Pin LL_GPIO_PIN_12
#define SPEAKER_GPIO_Port GPIOB
#define SPEAKER_Pin LL_GPIO_PIN_8
#define VIBRO_GPIO_Port GPIOA
#define VIBRO_Pin LL_GPIO_PIN_8
#define iBTN_GPIO_Port GPIOB
#define iBTN_Pin LL_GPIO_PIN_14
#define USART1_TX_Pin LL_GPIO_PIN_6
#define USART1_TX_Port GPIOB
#define USART1_RX_Pin LL_GPIO_PIN_7
#define USART1_RX_Port GPIOB
#define SPI_D_MISO_GPIO_Port GPIOC
#define SPI_D_MISO_Pin LL_GPIO_PIN_2
#define SPI_D_MOSI_GPIO_Port GPIOB
#define SPI_D_MOSI_Pin LL_GPIO_PIN_15
#define SPI_D_SCK_GPIO_Port GPIOD
#define SPI_D_SCK_Pin LL_GPIO_PIN_1
#define SPI_R_MISO_GPIO_Port GPIOB
#define SPI_R_MISO_Pin LL_GPIO_PIN_4
#define SPI_R_MOSI_GPIO_Port GPIOB
#define SPI_R_MOSI_Pin LL_GPIO_PIN_5
#define SPI_R_SCK_GPIO_Port GPIOA
#define SPI_R_SCK_Pin LL_GPIO_PIN_5
#define NFC_IRQ_Pin RFID_PULL_Pin
#define NFC_IRQ_GPIO_Port RFID_PULL_GPIO_Port
#ifdef __cplusplus
}
#endif

View File

@@ -1,40 +0,0 @@
/**
******************************************************************************
* @file stm32_assert.h
* @brief STM32 assert file.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2019 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32_ASSERT_H
#define __STM32_ASSERT_H
#ifdef __cplusplus
extern "C" {
#endif
#ifdef USE_FULL_ASSERT
#define assert_param(expr) ((expr) ? (void)0U : assert_failed())
void assert_failed();
#else
#define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* __STM32_ASSERT_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -1,347 +0,0 @@
/**
******************************************************************************
* @file stm32wbxx_hal_conf.h
* @author MCD Application Team
* @brief HAL configuration file.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2019 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32WBxx_HAL_CONF_H
#define __STM32WBxx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
/*#define HAL_ADC_MODULE_ENABLED */
#define HAL_CRYP_MODULE_ENABLED
/*#define HAL_COMP_MODULE_ENABLED */
/*#define HAL_CRC_MODULE_ENABLED */
/*#define HAL_HSEM_MODULE_ENABLED */
/*#define HAL_I2C_MODULE_ENABLED */
/*#define HAL_IPCC_MODULE_ENABLED */
/*#define HAL_IRDA_MODULE_ENABLED */
/*#define HAL_IWDG_MODULE_ENABLED */
/*#define HAL_LCD_MODULE_ENABLED */
/*#define HAL_LPTIM_MODULE_ENABLED */
#define HAL_PCD_MODULE_ENABLED
#define HAL_PKA_MODULE_ENABLED
/*#define HAL_QSPI_MODULE_ENABLED */
#define HAL_RNG_MODULE_ENABLED
/*#define HAL_RTC_MODULE_ENABLED */
/*#define HAL_SAI_MODULE_ENABLED */
/*#define HAL_SMBUS_MODULE_ENABLED */
/*#define HAL_SMARTCARD_MODULE_ENABLED */
/*#define HAL_SPI_MODULE_ENABLED */
/*#define HAL_TIM_MODULE_ENABLED */
/*#define HAL_TSC_MODULE_ENABLED */
/*#define HAL_UART_MODULE_ENABLED */
/*#define HAL_USART_MODULE_ENABLED */
/*#define HAL_WWDG_MODULE_ENABLED */
#define HAL_EXTI_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define USE_HAL_ADC_REGISTER_CALLBACKS 0u
#define USE_HAL_COMP_REGISTER_CALLBACKS 0u
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0u
#define USE_HAL_I2C_REGISTER_CALLBACKS 0u
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0u
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0u
#define USE_HAL_PCD_REGISTER_CALLBACKS 0u
#define USE_HAL_PKA_REGISTER_CALLBACKS 0u
#define USE_HAL_QSPI_REGISTER_CALLBACKS 0u
#define USE_HAL_RNG_REGISTER_CALLBACKS 0u
#define USE_HAL_RTC_REGISTER_CALLBACKS 0u
#define USE_HAL_SAI_REGISTER_CALLBACKS 0u
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0u
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0u
#define USE_HAL_SPI_REGISTER_CALLBACKS 0u
#define USE_HAL_TIM_REGISTER_CALLBACKS 0u
#define USE_HAL_TSC_REGISTER_CALLBACKS 0u
#define USE_HAL_UART_REGISTER_CALLBACKS 0u
#define USE_HAL_USART_REGISTER_CALLBACKS 0u
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0u
/* ########################## Oscillator Values adaptation ####################*/
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined(HSE_VALUE)
#define HSE_VALUE 32000000U /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined(HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal Multiple Speed oscillator (MSI) default value.
* This value is the default MSI range value after Reset.
*/
#if !defined(MSI_VALUE)
#define MSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* MSI_VALUE */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined(HSI_VALUE)
#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI1) value.
*/
#if !defined(LSI1_VALUE)
#define LSI1_VALUE ((uint32_t)32000) /*!< LSI1 Typical Value in Hz*/
#endif /* LSI1_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
in voltage and temperature.*/
/**
* @brief Internal Low Speed oscillator (LSI2) value.
*/
#if !defined(LSI2_VALUE)
#define LSI2_VALUE ((uint32_t)32000) /*!< LSI2 Typical Value in Hz*/
#endif /* LSI2_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
in voltage and temperature.*/
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined(LSE_VALUE)
#define LSE_VALUE 32768U /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
/**
* @brief Internal Multiple Speed oscillator (HSI48) default value.
* This value is the default HSI48 range value after Reset.
*/
#if !defined(HSI48_VALUE)
#define HSI48_VALUE ((uint32_t)48000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI48_VALUE */
#if !defined(LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT 1000U /*!< Time out for LSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for SAI1 peripheral
* This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source
* frequency.
*/
#if !defined(EXTERNAL_SAI1_CLOCK_VALUE)
#define EXTERNAL_SAI1_CLOCK_VALUE \
((uint32_t)2097000) /*!< Value of the SAI1 External clock source in Hz*/
#endif /* EXTERNAL_SAI1_CLOCK_VALUE */
/* Tip: To avoid modifying this file each time you need to use different HSE,
=== you can define the HSE value in your toolchain compiler preprocessor. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE 3300U /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY 0U /*!< tick interrupt priority */
#define USE_RTOS 0U
#define PREFETCH_ENABLE 1U
#define INSTRUCTION_CACHE_ENABLE 1U
#define DATA_CACHE_ENABLE 1U
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
#ifdef APP_UNIT_TESTS
#define USE_FULL_ASSERT 1U
#endif
/* ################## SPI peripheral configuration ########################## */
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
* Activated: CRC code is present inside driver
* Deactivated: CRC code cleaned from driver
*/
#define USE_SPI_CRC 0U
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32wbxx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32wbxx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32wbxx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32wbxx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32wbxx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32wbxx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32wbxx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32wbxx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32wbxx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_HSEM_MODULE_ENABLED
#include "stm32wbxx_hal_hsem.h"
#endif /* HAL_HSEM_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32wbxx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_IPCC_MODULE_ENABLED
#include "stm32wbxx_hal_ipcc.h"
#endif /* HAL_IPCC_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32wbxx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32wbxx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LCD_MODULE_ENABLED
#include "stm32wbxx_hal_lcd.h"
#endif /* HAL_LCD_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32wbxx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32wbxx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_PKA_MODULE_ENABLED
#include "stm32wbxx_hal_pka.h"
#endif /* HAL_PKA_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32wbxx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_QSPI_MODULE_ENABLED
#include "stm32wbxx_hal_qspi.h"
#endif /* HAL_QSPI_MODULE_ENABLED */
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32wbxx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32wbxx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32wbxx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SAI_MODULE_ENABLED
#include "stm32wbxx_hal_sai.h"
#endif /* HAL_SAI_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32wbxx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32wbxx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32wbxx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32wbxx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_TSC_MODULE_ENABLED
#include "stm32wbxx_hal_tsc.h"
#endif /* HAL_TSC_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32wbxx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32wbxx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32wbxx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
#define assert_param(expr) ((expr) ? (void)0U : assert_failed())
void assert_failed();
#else
#define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* __STM32WBxx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -1,131 +0,0 @@
#include "gpio.h"
void MX_GPIO_Init(void) {
GPIO_InitTypeDef GPIO_InitStruct = {0};
/*Configure GPIO pin : PtPin */
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING_FALLING;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Pin = BUTTON_BACK_Pin;
HAL_GPIO_Init(BUTTON_BACK_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pin : PtPin */
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING_FALLING;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Pin = BUTTON_OK_Pin;
HAL_GPIO_Init(BUTTON_OK_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pins : PCPin PCPin PCPin PCPin */
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Pin = PC0_Pin;
HAL_GPIO_Init(PC0_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = PC1_Pin;
HAL_GPIO_Init(PC1_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = PC3_Pin;
HAL_GPIO_Init(PC3_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = VIBRO_Pin;
HAL_GPIO_Init(VIBRO_GPIO_Port, &GPIO_InitStruct);
/* RF_SW_0 */
HAL_GPIO_WritePin(RF_SW_0_GPIO_Port, RF_SW_0_Pin, GPIO_PIN_RESET);
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Pin = RF_SW_0_Pin;
HAL_GPIO_Init(RF_SW_0_GPIO_Port, &GPIO_InitStruct);
/* PERIPH_POWER */
HAL_GPIO_WritePin(PERIPH_POWER_GPIO_Port, PERIPH_POWER_Pin, GPIO_PIN_SET);
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Pin = PERIPH_POWER_Pin;
HAL_GPIO_Init(PERIPH_POWER_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pins : PAPin PAPin PAPin */
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Pin = PA4_Pin;
HAL_GPIO_Init(PA4_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = PA6_Pin;
HAL_GPIO_Init(PA6_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = PA7_Pin;
HAL_GPIO_Init(PA7_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pin : PtPin */
GPIO_InitStruct.Pin = RFID_PULL_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(RFID_PULL_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pins : PBPin PBPin PBPin */
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Pin = PB2_Pin;
HAL_GPIO_Init(PB2_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = iBTN_Pin;
HAL_GPIO_Init(iBTN_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = PB3_Pin;
HAL_GPIO_Init(PB3_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pins : PBPin PBPin PBPin PBPin */
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING_FALLING;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Pin = BUTTON_UP_Pin;
HAL_GPIO_Init(BUTTON_UP_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = BUTTON_LEFT_Pin;
HAL_GPIO_Init(BUTTON_LEFT_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = BUTTON_RIGHT_Pin;
HAL_GPIO_Init(BUTTON_RIGHT_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pins : PBPin PBPin PBPin PBPin */
GPIO_InitStruct.Pin = BUTTON_DOWN_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING_FALLING;
GPIO_InitStruct.Pull = GPIO_PULLUP;
HAL_GPIO_Init(BUTTON_DOWN_GPIO_Port, &GPIO_InitStruct);
/* DISPLAY_RST */
HAL_GPIO_WritePin(DISPLAY_RST_GPIO_Port, DISPLAY_RST_Pin, GPIO_PIN_RESET);
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Pin = DISPLAY_RST_Pin;
HAL_GPIO_Init(DISPLAY_RST_GPIO_Port, &GPIO_InitStruct);
/* DISPLAY_DI */
HAL_GPIO_WritePin(DISPLAY_DI_GPIO_Port, DISPLAY_DI_Pin, GPIO_PIN_RESET);
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Pin = DISPLAY_DI_Pin;
HAL_GPIO_Init(DISPLAY_DI_GPIO_Port, &GPIO_InitStruct);
/* SD_CD */
GPIO_InitStruct.Pin = SD_CD_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(SD_CD_GPIO_Port, &GPIO_InitStruct);
/* Enable all NVIC lines related to gpio */
HAL_NVIC_SetPriority(EXTI0_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI0_IRQn);
HAL_NVIC_SetPriority(EXTI1_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI1_IRQn);
HAL_NVIC_SetPriority(EXTI2_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI2_IRQn);
HAL_NVIC_SetPriority(EXTI3_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI3_IRQn);
HAL_NVIC_SetPriority(EXTI4_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI4_IRQn);
HAL_NVIC_SetPriority(EXTI9_5_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI9_5_IRQn);
HAL_NVIC_SetPriority(EXTI15_10_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI15_10_IRQn);
}

View File

@@ -1,5 +1,3 @@
#include "main.h"
#include <furi.h>
#include <furi_hal.h>
#include <flipper.h>
@@ -13,9 +11,6 @@ int main(void) {
// Initialize FURI layer
furi_init();
// Initialize ST HAL
HAL_Init();
// Flipper FURI HAL
furi_hal_init();
@@ -32,20 +27,3 @@ int main(void) {
while(1) {
}
}
void Error_Handler(void) {
furi_crash("ErrorHandler");
}
#ifdef USE_FULL_ASSERT
/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t* file, uint32_t line) {
furi_crash("HAL assert failed");
}
#endif /* USE_FULL_ASSERT */

View File

@@ -149,29 +149,30 @@ void APPD_Init(void) {
/**
* Keep debugger enabled while in any low power mode
*/
HAL_DBGMCU_EnableDBGSleepMode();
HAL_DBGMCU_EnableDBGStopMode();
LL_DBGMCU_EnableDBGSleepMode();
LL_DBGMCU_EnableDBGStopMode();
/***************** ENABLE DEBUGGER *************************************/
LL_EXTI_EnableIT_32_63(LL_EXTI_LINE_48);
#else
GPIO_InitTypeDef gpio_config = {0};
LL_GPIO_InitTypeDef gpio_config = {0};
LL_PWR_EnableVddUSB();
gpio_config.Pull = GPIO_NOPULL;
gpio_config.Mode = GPIO_MODE_ANALOG;
gpio_config.Mode = LL_GPIO_MODE_ANALOG;
gpio_config.Speed = LL_GPIO_SPEED_FREQ_LOW;
// gpio_config.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
// gpio_config.Pull = LL_GPIO_PULL_NO;
// gpio_config.Alternate = LL_GPIO_AF_10;
gpio_config.Pin = LL_GPIO_PIN_15 | LL_GPIO_PIN_14 | LL_GPIO_PIN_13;
LL_GPIO_Init(GPIOA, &gpio_config);
gpio_config.Pin = GPIO_PIN_15 | GPIO_PIN_14 | GPIO_PIN_13;
__HAL_RCC_GPIOA_CLK_ENABLE();
HAL_GPIO_Init(GPIOA, &gpio_config);
gpio_config.Pin = LL_GPIO_PIN_4 | LL_GPIO_PIN_3;
LL_GPIO_Init(GPIOB, &gpio_config);
gpio_config.Pin = GPIO_PIN_4 | GPIO_PIN_3;
__HAL_RCC_GPIOB_CLK_ENABLE();
HAL_GPIO_Init(GPIOB, &gpio_config);
HAL_DBGMCU_DisableDBGSleepMode();
HAL_DBGMCU_DisableDBGStopMode();
HAL_DBGMCU_DisableDBGStandbyMode();
LL_DBGMCU_DisableDBGSleepMode();
LL_DBGMCU_DisableDBGStopMode();
LL_DBGMCU_DisableDBGStandbyMode();
#endif /* (CFG_DEBUGGER_SUPPORTED == 1) */
@@ -203,12 +204,12 @@ void APPD_EnableCPU2(void) {
/** GPIO DEBUG Initialization */
SHCI_C2_DEBUG_Init(&DebugCmdPacket);
// GPIO_InitTypeDef GPIO_InitStruct;
// GPIO_InitStruct.Pull = GPIO_NOPULL;
// GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
// GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
// GPIO_InitStruct.Pin = LL_GPIO_PIN_3;
// HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
// LL_GPIO_InitTypeDef gpio_config;
// gpio_config.Pull = GPIO_NOPULL;
// gpio_config.Mode = GPIO_MODE_OUTPUT_PP;
// gpio_config.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
// gpio_config.Pin = LL_GPIO_PIN_3;
// HAL_GPIO_Init(GPIOC, &gpio_config);
// SHCI_C2_ExtpaConfig((uint32_t)GPIOC, LL_GPIO_PIN_3, EXT_PA_ENABLED_LOW, EXT_PA_ENABLED);
/* USER CODE END APPD_EnableCPU2 */
@@ -222,7 +223,7 @@ void APPD_EnableCPU2(void) {
*************************************************************/
static void APPD_SetCPU2GpioConfig(void) {
/* USER CODE BEGIN APPD_SetCPU2GpioConfig */
GPIO_InitTypeDef gpio_config = {0};
LL_GPIO_InitTypeDef gpio_config = {0};
uint8_t local_loop;
uint16_t gpioa_pin_list;
uint16_t gpiob_pin_list;
@@ -253,32 +254,33 @@ static void APPD_SetCPU2GpioConfig(void) {
}
}
gpio_config.Pull = GPIO_NOPULL;
gpio_config.Mode = GPIO_MODE_OUTPUT_PP;
gpio_config.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
gpio_config.Mode = LL_GPIO_MODE_OUTPUT;
gpio_config.Speed = LL_GPIO_SPEED_FREQ_VERY_HIGH;
gpio_config.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
gpio_config.Pull = LL_GPIO_PULL_NO;
gpio_config.Pin = LL_GPIO_PIN_15 | LL_GPIO_PIN_14 | LL_GPIO_PIN_13;
LL_GPIO_Init(GPIOA, &gpio_config);
if(gpioa_pin_list != 0) {
gpio_config.Pin = gpioa_pin_list;
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_C2GPIOA_CLK_ENABLE();
HAL_GPIO_Init(GPIOA, &gpio_config);
HAL_GPIO_WritePin(GPIOA, gpioa_pin_list, GPIO_PIN_RESET);
LL_C2_AHB2_GRP1_EnableClock(LL_C2_AHB2_GRP1_PERIPH_GPIOA);
LL_GPIO_Init(GPIOA, &gpio_config);
LL_GPIO_ResetOutputPin(GPIOA, gpioa_pin_list);
}
if(gpiob_pin_list != 0) {
gpio_config.Pin = gpiob_pin_list;
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_C2GPIOB_CLK_ENABLE();
HAL_GPIO_Init(GPIOB, &gpio_config);
HAL_GPIO_WritePin(GPIOB, gpiob_pin_list, GPIO_PIN_RESET);
LL_C2_AHB2_GRP1_EnableClock(LL_C2_AHB2_GRP1_PERIPH_GPIOB);
LL_GPIO_Init(GPIOB, &gpio_config);
LL_GPIO_ResetOutputPin(GPIOB, gpioa_pin_list);
}
if(gpioc_pin_list != 0) {
gpio_config.Pin = gpioc_pin_list;
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_C2GPIOC_CLK_ENABLE();
HAL_GPIO_Init(GPIOC, &gpio_config);
HAL_GPIO_WritePin(GPIOC, gpioc_pin_list, GPIO_PIN_RESET);
LL_C2_AHB2_GRP1_EnableClock(LL_C2_AHB2_GRP1_PERIPH_GPIOC);
LL_GPIO_Init(GPIOC, &gpio_config);
LL_GPIO_ResetOutputPin(GPIOC, gpioa_pin_list);
}
/* USER CODE END APPD_SetCPU2GpioConfig */
@@ -288,7 +290,7 @@ static void APPD_SetCPU2GpioConfig(void) {
static void APPD_BleDtbCfg(void) {
/* USER CODE BEGIN APPD_BleDtbCfg */
#if(BLE_DTB_CFG != 0)
GPIO_InitTypeDef gpio_config = {0};
LL_GPIO_InitTypeDef gpio_config = {0};
uint8_t local_loop;
uint16_t gpioa_pin_list;
uint16_t gpiob_pin_list;
@@ -313,23 +315,23 @@ static void APPD_BleDtbCfg(void) {
}
}
gpio_config.Pull = GPIO_NOPULL;
gpio_config.Mode = GPIO_MODE_AF_PP;
gpio_config.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
gpio_config.Alternate = GPIO_AF6_RF_DTB7;
gpio_config.Mode = LL_GPIO_MODE_ALTERNATE;
gpio_config.Speed = LL_GPIO_SPEED_FREQ_VERY_HIGH;
gpio_config.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
gpio_config.Pull = LL_GPIO_PULL_NO;
gpio_config.Alternate = LL_GPIO_AF_6;
gpio_config.Pin = LL_GPIO_PIN_15 | LL_GPIO_PIN_14 | LL_GPIO_PIN_13;
if(gpioa_pin_list != 0) {
gpio_config.Pin = gpioa_pin_list;
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_C2GPIOA_CLK_ENABLE();
HAL_GPIO_Init(GPIOA, &gpio_config);
LL_C2_AHB2_GRP1_EnableClock(LL_C2_AHB2_GRP1_PERIPH_GPIOA);
LL_GPIO_Init(GPIOA, &gpio_config);
}
if(gpiob_pin_list != 0) {
gpio_config.Pin = gpiob_pin_list;
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_C2GPIOB_CLK_ENABLE();
HAL_GPIO_Init(GPIOB, &gpio_config);
LL_C2_AHB2_GRP1_EnableClock(LL_C2_AHB2_GRP1_PERIPH_GPIOB);
LL_GPIO_Init(GPIOB, &gpio_config);
}
#endif

View File

@@ -23,6 +23,10 @@
#include "app_conf.h"
#ifndef __weak
#define __weak __attribute__((weak))
#endif
/******************************************************************************
*
* BLE SERVICES CONFIGURATION

View File

@@ -1,6 +1,5 @@
#include "ble_glue.h"
#include "app_common.h"
#include "main.h"
#include "ble_app.h"
#include "ble.h"
#include "tl.h"

View File

@@ -185,10 +185,10 @@ void HW_IPCC_Init(void) {
LL_C1_IPCC_EnableIT_RXO(IPCC);
LL_C1_IPCC_EnableIT_TXF(IPCC);
HAL_NVIC_SetPriority(IPCC_C1_RX_IRQn, 6, 0);
HAL_NVIC_EnableIRQ(IPCC_C1_RX_IRQn);
HAL_NVIC_SetPriority(IPCC_C1_TX_IRQn, 6, 0);
HAL_NVIC_EnableIRQ(IPCC_C1_TX_IRQn);
NVIC_SetPriority(IPCC_C1_RX_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 6, 0));
NVIC_EnableIRQ(IPCC_C1_RX_IRQn);
NVIC_SetPriority(IPCC_C1_TX_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 6, 0));
NVIC_EnableIRQ(IPCC_C1_TX_IRQn);
return;
}

View File

@@ -24,9 +24,6 @@
/ Additional user header to be used
/-----------------------------------------------------------------------------*/
#include "main.h"
#include "stm32wbxx_hal.h"
/*-----------------------------------------------------------------------------/
/ Function Configurations
/-----------------------------------------------------------------------------*/

View File

@@ -1,4 +1,3 @@
#include "main.h"
#include <furi_hal.h>
#include <furi.h>
@@ -46,8 +45,8 @@ void SD_IO_Init(void) {
uint8_t counter = 0;
/* SD chip select high */
hal_gpio_write(furi_hal_sd_spi_handle->cs, true);
delay_us(10);
furi_hal_gpio_write(furi_hal_sd_spi_handle->cs, true);
furi_hal_delay_us(10);
/* Send dummy byte 0xFF, 10 times with CS high */
/* Rise CS and MOSI for 80 clocks cycles */
@@ -65,11 +64,11 @@ void SD_IO_Init(void) {
void SD_IO_CSState(uint8_t val) {
/* Some SD Cards are prone to fail if CLK-ed too soon after CS transition. Worst case found: 8us */
if(val == 1) {
delay_us(10); // Exit guard time for some SD cards
hal_gpio_write(furi_hal_sd_spi_handle->cs, true);
furi_hal_delay_us(10); // Exit guard time for some SD cards
furi_hal_gpio_write(furi_hal_sd_spi_handle->cs, true);
} else {
hal_gpio_write(furi_hal_sd_spi_handle->cs, false);
delay_us(10); // Entry guard time for some SD cards
furi_hal_gpio_write(furi_hal_sd_spi_handle->cs, false);
furi_hal_delay_us(10); // Entry guard time for some SD cards
}
}

View File

@@ -279,47 +279,47 @@ static uint8_t SD_ReadData(void);
/* Private functions ---------------------------------------------------------*/
void SD_SPI_Bus_To_Down_State() {
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
furi_hal_sd_spi_handle->miso,
GpioModeOutputPushPull,
GpioPullNo,
GpioSpeedVeryHigh,
GpioAltFnUnused);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
furi_hal_sd_spi_handle->mosi,
GpioModeOutputPushPull,
GpioPullNo,
GpioSpeedVeryHigh,
GpioAltFnUnused);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
furi_hal_sd_spi_handle->sck,
GpioModeOutputPushPull,
GpioPullNo,
GpioSpeedVeryHigh,
GpioAltFnUnused);
hal_gpio_write(furi_hal_sd_spi_handle->cs, false);
hal_gpio_write(furi_hal_sd_spi_handle->miso, false);
hal_gpio_write(furi_hal_sd_spi_handle->mosi, false);
hal_gpio_write(furi_hal_sd_spi_handle->sck, false);
furi_hal_gpio_write(furi_hal_sd_spi_handle->cs, false);
furi_hal_gpio_write(furi_hal_sd_spi_handle->miso, false);
furi_hal_gpio_write(furi_hal_sd_spi_handle->mosi, false);
furi_hal_gpio_write(furi_hal_sd_spi_handle->sck, false);
}
void SD_SPI_Bus_To_Normal_State() {
hal_gpio_write(furi_hal_sd_spi_handle->cs, true);
furi_hal_gpio_write(furi_hal_sd_spi_handle->cs, true);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
furi_hal_sd_spi_handle->miso,
GpioModeAltFunctionPushPull,
GpioPullUp,
GpioSpeedVeryHigh,
GpioAltFn5SPI2);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
furi_hal_sd_spi_handle->mosi,
GpioModeAltFunctionPushPull,
GpioPullUp,
GpioSpeedVeryHigh,
GpioAltFn5SPI2);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
furi_hal_sd_spi_handle->sck,
GpioModeAltFunctionPushPull,
GpioPullUp,
@@ -349,13 +349,13 @@ uint8_t BSP_SD_Init(bool reset_card) {
furi_hal_power_disable_external_3_3v();
SD_SPI_Bus_To_Down_State();
hal_sd_detect_set_low();
delay(250);
furi_hal_delay_ms(250);
/* reinit bus and enable power */
SD_SPI_Bus_To_Normal_State();
hal_sd_detect_init();
furi_hal_power_enable_external_3_3v();
delay(100);
furi_hal_delay_ms(100);
}
/* Configure IO functionalities for SD pin */
@@ -867,7 +867,7 @@ SD_CmdAnswer_typedef SD_SendCmd(uint8_t Cmd, uint32_t Arg, uint8_t Crc, uint8_t
retr.r2 = SD_IO_WriteByte(SD_DUMMY_BYTE);
/* Set CS High */
SD_IO_CSState(1);
HAL_Delay(1);
furi_hal_delay_us(1000);
/* Set CS Low */
SD_IO_CSState(0);

View File

@@ -1,7 +1,5 @@
#include <furi_hal.h>
#include <gpio.h>
#include <stm32wbxx_ll_cortex.h>
#include <fatfs.h>
@@ -13,7 +11,7 @@ void furi_hal_init() {
furi_hal_interrupt_init();
furi_hal_delay_init();
MX_GPIO_Init();
furi_hal_resources_init();
FURI_LOG_I(TAG, "GPIO OK");
furi_hal_bootloader_init();

View File

@@ -4,9 +4,12 @@
#include <stm32wbxx_ll_pwr.h>
#include <stm32wbxx_ll_rcc.h>
#include <stm32wbxx_ll_utils.h>
#include <stm32wbxx_ll_cortex.h>
#include <stm32wbxx_ll_bus.h>
#define TAG "FuriHalClock"
#define TICK_INT_PRIORITY 0U
#define HS_CLOCK_IS_READY() (LL_RCC_HSE_IsReady() && LL_RCC_HSI_IsReady())
#define LS_CLOCK_IS_READY() (LL_RCC_LSE_IsReady() && LL_RCC_LSI1_IsReady())
@@ -83,9 +86,10 @@ void furi_hal_clock_init() {
LL_SetSystemCoreClock(64000000);
/* Update the time base */
if(HAL_InitTick(TICK_INT_PRIORITY) != HAL_OK) {
Error_Handler();
}
LL_InitTick(64000000, 1000);
LL_SYSTICK_EnableIT();
NVIC_SetPriority(SysTick_IRQn, TICK_INT_PRIORITY);
NVIC_EnableIRQ(SysTick_IRQn);
LL_RCC_SetUSARTClockSource(LL_RCC_USART1_CLKSOURCE_PCLK2);
LL_RCC_SetLPUARTClockSource(LL_RCC_LPUART1_CLKSOURCE_PCLK1);

View File

@@ -1,16 +1,27 @@
#include <furi_hal_crypto.h>
#include <furi_hal_bt.h>
#include <furi_hal_random.h>
#include <stm32wbxx_ll_cortex.h>
#include <furi.h>
#include <shci.h>
#define TAG "FuriHalCrypto"
CRYP_HandleTypeDef crypt;
#define ENCLAVE_FACTORY_KEY_SLOTS 10
#define ENCLAVE_SIGNATURE_SIZE 16
#define CRYPTO_BLK_LEN (4 * sizeof(uint32_t))
#define CRYPTO_TIMEOUT (1000)
#define CRYPTO_MODE_ENCRYPT 0U
#define CRYPTO_MODE_DECRYPT (AES_CR_MODE_1)
#define CRYPTO_MODE_DECRYPT_INIT (AES_CR_MODE_0 | AES_CR_MODE_1)
#define CRYPTO_DATATYPE_32B 0U
#define CRYPTO_KEYSIZE_256B (AES_CR_KEYSIZE)
#define CRYPTO_AES_CBC (AES_CR_CHMOD_0)
static osMutexId_t furi_hal_crypto_mutex = NULL;
static const uint8_t enclave_signature_iv[ENCLAVE_FACTORY_KEY_SLOTS][16] = {
{0xac, 0x5d, 0x68, 0xb8, 0x79, 0x74, 0xfc, 0x7f, 0x45, 0x02, 0x82, 0xf1, 0x48, 0x7e, 0x75, 0x8a},
{0x38, 0xe6, 0x6a, 0x90, 0x5e, 0x5b, 0x8a, 0xa6, 0x70, 0x30, 0x04, 0x72, 0xc2, 0x42, 0xea, 0xaf},
@@ -51,6 +62,7 @@ static const uint8_t enclave_signature_expected[ENCLAVE_FACTORY_KEY_SLOTS][ENCLA
};
void furi_hal_crypto_init() {
furi_hal_crypto_mutex = osMutexNew(NULL);
FURI_LOG_I(TAG, "Init OK");
}
@@ -127,6 +139,8 @@ bool furi_hal_crypto_store_add_key(FuriHalCryptoKey* key, uint8_t* slot) {
furi_assert(key);
furi_assert(slot);
furi_check(osMutexAcquire(furi_hal_crypto_mutex, osWaitForever) == osOK);
if(!furi_hal_bt_is_alive()) {
return false;
}
@@ -157,30 +171,91 @@ bool furi_hal_crypto_store_add_key(FuriHalCryptoKey* key, uint8_t* slot) {
memcpy(pParam.KeyData, key->data, key_data_size);
return SHCI_C2_FUS_StoreUsrKey(&pParam, slot) == SHCI_Success;
SHCI_CmdStatus_t shci_state = SHCI_C2_FUS_StoreUsrKey(&pParam, slot);
furi_check(osMutexRelease(furi_hal_crypto_mutex) == osOK);
return (shci_state == SHCI_Success);
}
static void crypto_enable() {
SET_BIT(AES1->CR, AES_CR_EN);
}
static void crypto_disable() {
CLEAR_BIT(AES1->CR, AES_CR_EN);
}
static void crypto_key_init(uint32_t* key, uint32_t* iv) {
crypto_disable();
MODIFY_REG(
AES1->CR,
AES_CR_DATATYPE | AES_CR_KEYSIZE | AES_CR_CHMOD,
CRYPTO_DATATYPE_32B | CRYPTO_KEYSIZE_256B | CRYPTO_AES_CBC);
if(key != NULL) {
AES1->KEYR7 = key[0];
AES1->KEYR6 = key[1];
AES1->KEYR5 = key[2];
AES1->KEYR4 = key[3];
AES1->KEYR3 = key[4];
AES1->KEYR2 = key[5];
AES1->KEYR1 = key[6];
AES1->KEYR0 = key[7];
}
AES1->IVR3 = iv[0];
AES1->IVR2 = iv[1];
AES1->IVR1 = iv[2];
AES1->IVR0 = iv[3];
}
static bool crypto_process_block(uint32_t* in, uint32_t* out, uint8_t blk_len) {
furi_check((blk_len <= 4) && (blk_len > 0));
for(uint8_t i = 0; i < 4; i++) {
if(i < blk_len) {
AES1->DINR = in[i];
} else {
AES1->DINR = 0;
}
}
uint32_t countdown = CRYPTO_TIMEOUT;
while(!READ_BIT(AES1->SR, AES_SR_CCF)) {
if(LL_SYSTICK_IsActiveCounterFlag()) {
countdown--;
}
if(countdown == 0) {
return false;
}
}
SET_BIT(AES1->CR, AES_CR_CCFC);
uint32_t out_temp[4];
for(uint8_t i = 0; i < 4; i++) {
out_temp[i] = AES1->DOUTR;
}
memcpy(out, out_temp, blk_len * sizeof(uint32_t));
return true;
}
bool furi_hal_crypto_store_load_key(uint8_t slot, const uint8_t* iv) {
furi_assert(slot > 0 && slot <= 100);
furi_assert(furi_hal_crypto_mutex);
furi_check(osMutexAcquire(furi_hal_crypto_mutex, osWaitForever) == osOK);
if(!furi_hal_bt_is_alive()) {
return false;
}
crypt.Instance = AES1;
crypt.Init.DataType = CRYP_DATATYPE_32B;
crypt.Init.KeySize = CRYP_KEYSIZE_256B;
crypt.Init.Algorithm = CRYP_AES_CBC;
crypt.Init.pInitVect = (uint32_t*)iv;
crypt.Init.KeyIVConfigSkip = CRYP_KEYIVCONFIG_ONCE;
crypt.Init.pKey = NULL;
furi_check(HAL_CRYP_Init(&crypt) == HAL_OK);
crypto_key_init(NULL, (uint32_t*)iv);
if(SHCI_C2_FUS_LoadUsrKey(slot) == SHCI_Success) {
return true;
} else {
furi_check(HAL_CRYP_DeInit(&crypt) == HAL_OK);
crypto_disable();
furi_check(osMutexRelease(furi_hal_crypto_mutex) == osOK);
return false;
}
}
@@ -190,14 +265,55 @@ bool furi_hal_crypto_store_unload_key(uint8_t slot) {
return false;
}
furi_check(HAL_CRYP_DeInit(&crypt) == HAL_OK);
return SHCI_C2_FUS_UnloadUsrKey(slot) == SHCI_Success;
crypto_disable();
SHCI_CmdStatus_t shci_state = SHCI_C2_FUS_UnloadUsrKey(slot);
furi_check(osMutexRelease(furi_hal_crypto_mutex) == osOK);
return (shci_state == SHCI_Success);
}
bool furi_hal_crypto_encrypt(const uint8_t* input, uint8_t* output, size_t size) {
return HAL_CRYP_Encrypt(&crypt, (uint32_t*)input, size / 4, (uint32_t*)output, 1000) == HAL_OK;
bool state = false;
crypto_enable();
MODIFY_REG(AES1->CR, AES_CR_MODE, CRYPTO_MODE_ENCRYPT);
for(size_t i = 0; i < size; i += CRYPTO_BLK_LEN) {
size_t blk_len = size - i;
if(blk_len > CRYPTO_BLK_LEN) {
blk_len = CRYPTO_BLK_LEN;
}
state = crypto_process_block((uint32_t*)&input[i], (uint32_t*)&output[i], blk_len / 4);
if(state == false) {
break;
}
}
crypto_disable();
return state;
}
bool furi_hal_crypto_decrypt(const uint8_t* input, uint8_t* output, size_t size) {
return HAL_CRYP_Decrypt(&crypt, (uint32_t*)input, size / 4, (uint32_t*)output, 1000) == HAL_OK;
bool state = false;
MODIFY_REG(AES1->CR, AES_CR_MODE, CRYPTO_MODE_DECRYPT_INIT);
crypto_enable();
for(size_t i = 0; i < size; i += CRYPTO_BLK_LEN) {
size_t blk_len = size - i;
if(blk_len > CRYPTO_BLK_LEN) {
blk_len = CRYPTO_BLK_LEN;
}
state = crypto_process_block((uint32_t*)&input[i], (uint32_t*)&output[i], blk_len / 4);
if(state == false) {
break;
}
}
crypto_disable();
return state;
}

View File

@@ -5,6 +5,7 @@
#define TAG "FuriHalDelay"
uint32_t instructions_per_us;
static volatile uint32_t tick_cnt = 0;
void furi_hal_delay_init(void) {
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
@@ -14,7 +15,15 @@ void furi_hal_delay_init(void) {
FURI_LOG_I(TAG, "Init OK");
}
void delay_us(float microseconds) {
void furi_hal_tick(void) {
tick_cnt++;
}
uint32_t furi_hal_get_tick(void) {
return tick_cnt;
}
void furi_hal_delay_us(float microseconds) {
uint32_t start = DWT->CYCCNT;
uint32_t time_ticks = microseconds * instructions_per_us;
while((DWT->CYCCNT - start) < time_ticks) {
@@ -23,13 +32,9 @@ void delay_us(float microseconds) {
// cannot be used in ISR
// TODO add delay_ISR variant
void delay(float milliseconds) {
void furi_hal_delay_ms(float milliseconds) {
uint32_t ticks = milliseconds / (1000.0f / osKernelGetTickFreq());
osStatus_t result = osDelay(ticks);
(void)result;
furi_assert(result == osOK);
}
uint32_t millis(void) {
return HAL_GetTick();
}

View File

@@ -12,6 +12,17 @@
#define FURI_HAL_FLASH_WRITE_BLOCK 8
#define FURI_HAL_FLASH_PAGE_SIZE 4096
#define FURI_HAL_FLASH_CYCLES_COUNT 10000
#define FURI_HAL_FLASH_TIMEOUT 1000
#define FURI_HAL_FLASH_KEY1 0x45670123U
#define FURI_HAL_FLASH_KEY2 0xCDEF89ABU
#define FURI_HAL_FLASH_SR_ERRORS \
(FLASH_SR_OPERR | FLASH_SR_PROGERR | FLASH_SR_WRPERR | FLASH_SR_PGAERR | FLASH_SR_SIZERR | \
FLASH_SR_PGSERR | FLASH_SR_MISERR | FLASH_SR_FASTERR | FLASH_SR_RDERR | FLASH_SR_OPTVERR)
#define IS_ADDR_ALIGNED_64BITS(__VALUE__) (((__VALUE__)&0x7U) == (0x00UL))
#define IS_FLASH_PROGRAM_ADDRESS(__VALUE__) \
(((__VALUE__) >= FLASH_BASE) && ((__VALUE__) <= (FLASH_BASE + FLASH_SIZE - 8UL)) && \
(((__VALUE__) % 8UL) == 0UL))
/* Free flash space borders, exported by linker */
extern const void __free_flash_start__;
@@ -43,7 +54,7 @@ const void* furi_hal_flash_get_free_start_address() {
const void* furi_hal_flash_get_free_end_address() {
uint32_t sfr_reg_val = READ_REG(FLASH->SFR);
uint32_t sfsa = (READ_BIT(sfr_reg_val, FLASH_SFR_SFSA) >> FLASH_SFR_SFSA_Pos);
return (const void*)((sfsa * FLASH_PAGE_SIZE) + FLASH_BASE);
return (const void*)((sfsa * FURI_HAL_FLASH_PAGE_SIZE) + FLASH_BASE);
}
size_t furi_hal_flash_get_free_page_start_address() {
@@ -66,8 +77,8 @@ static void furi_hal_flash_unlock() {
furi_check(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != 0U);
/* Authorize the FLASH Registers access */
WRITE_REG(FLASH->KEYR, FLASH_KEY1);
WRITE_REG(FLASH->KEYR, FLASH_KEY2);
WRITE_REG(FLASH->KEYR, FURI_HAL_FLASH_KEY1);
WRITE_REG(FLASH->KEYR, FURI_HAL_FLASH_KEY2);
/* verify Flash is unlock */
furi_check(READ_BIT(FLASH->CR, FLASH_CR_LOCK) == 0U);
@@ -152,7 +163,7 @@ static void furi_hal_flash_end_with_core2(bool erase_flag) {
taskEXIT_CRITICAL();
// Doesn't make much sense, does it?
while(__HAL_FLASH_GET_FLAG(FLASH_FLAG_BSY)) {
while(READ_BIT(FLASH->SR, FLASH_SR_BSY)) {
osThreadYield();
}
@@ -202,7 +213,7 @@ static void furi_hal_flush_cache(void) {
}
}
HAL_StatusTypeDef furi_hal_flash_wait_last_operation(uint32_t timeout) {
bool furi_hal_flash_wait_last_operation(uint32_t timeout) {
uint32_t error = 0;
uint32_t countdown = 0;
@@ -210,12 +221,12 @@ HAL_StatusTypeDef furi_hal_flash_wait_last_operation(uint32_t timeout) {
// Even if the FLASH operation fails, the BUSY flag will be reset and an error
// flag will be set
countdown = timeout;
while(__HAL_FLASH_GET_FLAG(FLASH_FLAG_BSY)) {
while(READ_BIT(FLASH->SR, FLASH_SR_BSY)) {
if(LL_SYSTICK_IsActiveCounterFlag()) {
countdown--;
}
if(countdown == 0) {
return HAL_TIMEOUT;
return false;
}
}
@@ -223,31 +234,30 @@ HAL_StatusTypeDef furi_hal_flash_wait_last_operation(uint32_t timeout) {
error = FLASH->SR;
/* Check FLASH End of Operation flag */
if((error & FLASH_FLAG_EOP) != 0U) {
if((error & FLASH_SR_EOP) != 0U) {
/* Clear FLASH End of Operation pending bit */
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP);
CLEAR_BIT(FLASH->SR, FLASH_SR_EOP);
}
/* Now update error variable to only error value */
error &= FLASH_FLAG_SR_ERRORS;
error &= FURI_HAL_FLASH_SR_ERRORS;
furi_check(error == 0);
/* clear error flags */
__HAL_FLASH_CLEAR_FLAG(error);
CLEAR_BIT(FLASH->SR, error);
/* Wait for control register to be written */
countdown = timeout;
while(__HAL_FLASH_GET_FLAG(FLASH_FLAG_CFGBSY)) {
while(READ_BIT(FLASH->SR, FLASH_SR_CFGBSY)) {
if(LL_SYSTICK_IsActiveCounterFlag()) {
countdown--;
}
if(countdown == 0) {
return HAL_TIMEOUT;
return false;
}
}
return HAL_OK;
return true;
}
bool furi_hal_flash_erase(uint8_t page) {
@@ -257,14 +267,14 @@ bool furi_hal_flash_erase(uint8_t page) {
furi_check(FLASH->SR == 0);
/* Verify that next operation can be proceed */
furi_check(furi_hal_flash_wait_last_operation(FLASH_TIMEOUT_VALUE) == HAL_OK);
furi_check(furi_hal_flash_wait_last_operation(FURI_HAL_FLASH_TIMEOUT));
/* Select page and start operation */
MODIFY_REG(
FLASH->CR, FLASH_CR_PNB, ((page << FLASH_CR_PNB_Pos) | FLASH_CR_PER | FLASH_CR_STRT));
/* Wait for last operation to be completed */
furi_check(furi_hal_flash_wait_last_operation(FLASH_TIMEOUT_VALUE) == HAL_OK);
furi_check(furi_hal_flash_wait_last_operation(FURI_HAL_FLASH_TIMEOUT));
/* If operation is completed or interrupted, disable the Page Erase Bit */
CLEAR_BIT(FLASH->CR, (FLASH_CR_PER | FLASH_CR_PNB));
@@ -301,7 +311,7 @@ bool furi_hal_flash_write_dword(size_t address, uint64_t data) {
*(uint32_t*)(address + 4U) = (uint32_t)(data >> 32U);
/* Wait for last operation to be completed */
furi_check(furi_hal_flash_wait_last_operation(FLASH_TIMEOUT_VALUE) == HAL_OK);
furi_check(furi_hal_flash_wait_last_operation(FURI_HAL_FLASH_TIMEOUT));
/* If the program operation is completed, disable the PG or FSTPG Bit */
CLEAR_BIT(FLASH->CR, FLASH_CR_PG);

View File

@@ -34,7 +34,7 @@
static volatile GpioInterrupt gpio_interrupt[GPIO_NUMBER];
static uint8_t hal_gpio_get_pin_num(const GpioPin* gpio) {
static uint8_t furi_hal_gpio_get_pin_num(const GpioPin* gpio) {
uint8_t pin_num = 0;
for(pin_num = 0; pin_num < GPIO_NUMBER; pin_num++) {
if(gpio->pin & (1 << pin_num)) break;
@@ -42,11 +42,11 @@ static uint8_t hal_gpio_get_pin_num(const GpioPin* gpio) {
return pin_num;
}
void hal_gpio_init_simple(const GpioPin* gpio, const GpioMode mode) {
hal_gpio_init(gpio, mode, GpioPullNo, GpioSpeedLow);
void furi_hal_gpio_init_simple(const GpioPin* gpio, const GpioMode mode) {
furi_hal_gpio_init(gpio, mode, GpioPullNo, GpioSpeedLow);
}
void hal_gpio_init(
void furi_hal_gpio_init(
const GpioPin* gpio,
const GpioMode mode,
const GpioPull pull,
@@ -55,10 +55,10 @@ void hal_gpio_init(
furi_assert(mode != GpioModeAltFunctionPushPull);
furi_assert(mode != GpioModeAltFunctionOpenDrain);
hal_gpio_init_ex(gpio, mode, pull, speed, GpioAltFnUnused);
furi_hal_gpio_init_ex(gpio, mode, pull, speed, GpioAltFnUnused);
}
void hal_gpio_init_ex(
void furi_hal_gpio_init_ex(
const GpioPin* gpio,
const GpioMode mode,
const GpioPull pull,
@@ -133,7 +133,7 @@ void hal_gpio_init_ex(
// Prepare alternative part if any
if(mode == GpioModeAltFunctionPushPull || mode == GpioModeAltFunctionOpenDrain) {
// set alternate function
if(hal_gpio_get_pin_num(gpio) < 8) {
if(furi_hal_gpio_get_pin_num(gpio) < 8) {
LL_GPIO_SetAFPin_0_7(gpio->port, gpio->pin, alt_fn);
} else {
LL_GPIO_SetAFPin_8_15(gpio->port, gpio->pin, alt_fn);
@@ -171,12 +171,12 @@ void hal_gpio_init_ex(
FURI_CRITICAL_EXIT();
}
void hal_gpio_add_int_callback(const GpioPin* gpio, GpioExtiCallback cb, void* ctx) {
void furi_hal_gpio_add_int_callback(const GpioPin* gpio, GpioExtiCallback cb, void* ctx) {
furi_assert(gpio);
furi_assert(cb);
FURI_CRITICAL_ENTER();
uint8_t pin_num = hal_gpio_get_pin_num(gpio);
uint8_t pin_num = furi_hal_gpio_get_pin_num(gpio);
furi_assert(gpio_interrupt[pin_num].callback == NULL);
gpio_interrupt[pin_num].callback = cb;
gpio_interrupt[pin_num].context = ctx;
@@ -184,38 +184,38 @@ void hal_gpio_add_int_callback(const GpioPin* gpio, GpioExtiCallback cb, void* c
FURI_CRITICAL_EXIT();
}
void hal_gpio_enable_int_callback(const GpioPin* gpio) {
void furi_hal_gpio_enable_int_callback(const GpioPin* gpio) {
furi_assert(gpio);
FURI_CRITICAL_ENTER();
uint8_t pin_num = hal_gpio_get_pin_num(gpio);
uint8_t pin_num = furi_hal_gpio_get_pin_num(gpio);
if(gpio_interrupt[pin_num].callback) {
gpio_interrupt[pin_num].ready = true;
}
FURI_CRITICAL_EXIT();
}
void hal_gpio_disable_int_callback(const GpioPin* gpio) {
void furi_hal_gpio_disable_int_callback(const GpioPin* gpio) {
furi_assert(gpio);
FURI_CRITICAL_ENTER();
uint8_t pin_num = hal_gpio_get_pin_num(gpio);
uint8_t pin_num = furi_hal_gpio_get_pin_num(gpio);
gpio_interrupt[pin_num].ready = false;
FURI_CRITICAL_EXIT();
}
void hal_gpio_remove_int_callback(const GpioPin* gpio) {
void furi_hal_gpio_remove_int_callback(const GpioPin* gpio) {
furi_assert(gpio);
FURI_CRITICAL_ENTER();
uint8_t pin_num = hal_gpio_get_pin_num(gpio);
uint8_t pin_num = furi_hal_gpio_get_pin_num(gpio);
gpio_interrupt[pin_num].callback = NULL;
gpio_interrupt[pin_num].context = NULL;
gpio_interrupt[pin_num].ready = false;
FURI_CRITICAL_EXIT();
}
static void hal_gpio_int_call(uint16_t pin_num) {
static void furi_hal_gpio_int_call(uint16_t pin_num) {
if(gpio_interrupt[pin_num].callback && gpio_interrupt[pin_num].ready) {
gpio_interrupt[pin_num].callback(gpio_interrupt[pin_num].context);
}
@@ -225,84 +225,84 @@ static void hal_gpio_int_call(uint16_t pin_num) {
void EXTI0_IRQHandler(void) {
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_0)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_0);
hal_gpio_int_call(0);
furi_hal_gpio_int_call(0);
}
}
void EXTI1_IRQHandler(void) {
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_1)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_1);
hal_gpio_int_call(1);
furi_hal_gpio_int_call(1);
}
}
void EXTI2_IRQHandler(void) {
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_2)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_2);
hal_gpio_int_call(2);
furi_hal_gpio_int_call(2);
}
}
void EXTI3_IRQHandler(void) {
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_3)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_3);
hal_gpio_int_call(3);
furi_hal_gpio_int_call(3);
}
}
void EXTI4_IRQHandler(void) {
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_4)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_4);
hal_gpio_int_call(4);
furi_hal_gpio_int_call(4);
}
}
void EXTI9_5_IRQHandler(void) {
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_5)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_5);
hal_gpio_int_call(5);
furi_hal_gpio_int_call(5);
}
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_6)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_6);
hal_gpio_int_call(6);
furi_hal_gpio_int_call(6);
}
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_7)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_7);
hal_gpio_int_call(7);
furi_hal_gpio_int_call(7);
}
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_8)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_8);
hal_gpio_int_call(8);
furi_hal_gpio_int_call(8);
}
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_9)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_9);
hal_gpio_int_call(9);
furi_hal_gpio_int_call(9);
}
}
void EXTI15_10_IRQHandler(void) {
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_10)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_10);
hal_gpio_int_call(10);
furi_hal_gpio_int_call(10);
}
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_11)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_11);
hal_gpio_int_call(11);
furi_hal_gpio_int_call(11);
}
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_12)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_12);
hal_gpio_int_call(12);
furi_hal_gpio_int_call(12);
}
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_13)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_13);
hal_gpio_int_call(13);
furi_hal_gpio_int_call(13);
}
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_14)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_14);
hal_gpio_int_call(14);
furi_hal_gpio_int_call(14);
}
if(LL_EXTI_IsActiveFlag_0_31(LL_EXTI_LINE_15)) {
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_15);
hal_gpio_int_call(15);
furi_hal_gpio_int_call(15);
}
}

View File

@@ -1,5 +1,4 @@
#pragma once
#include "main.h"
#include "stdbool.h"
#include <stm32wbxx_ll_gpio.h>
#include <stm32wbxx_ll_system.h>
@@ -170,7 +169,7 @@ typedef struct {
* @param gpio GpioPin
* @param mode GpioMode
*/
void hal_gpio_init_simple(const GpioPin* gpio, const GpioMode mode);
void furi_hal_gpio_init_simple(const GpioPin* gpio, const GpioMode mode);
/**
* GPIO initialization function, normal version
@@ -179,7 +178,7 @@ void hal_gpio_init_simple(const GpioPin* gpio, const GpioMode mode);
* @param pull GpioPull
* @param speed GpioSpeed
*/
void hal_gpio_init(
void furi_hal_gpio_init(
const GpioPin* gpio,
const GpioMode mode,
const GpioPull pull,
@@ -193,7 +192,7 @@ void hal_gpio_init(
* @param speed GpioSpeed
* @param alt_fn GpioAltFn
*/
void hal_gpio_init_ex(
void furi_hal_gpio_init_ex(
const GpioPin* gpio,
const GpioMode mode,
const GpioPull pull,
@@ -206,32 +205,32 @@ void hal_gpio_init_ex(
* @param cb GpioExtiCallback
* @param ctx context for callback
*/
void hal_gpio_add_int_callback(const GpioPin* gpio, GpioExtiCallback cb, void* ctx);
void furi_hal_gpio_add_int_callback(const GpioPin* gpio, GpioExtiCallback cb, void* ctx);
/**
* Enable interrupt
* @param gpio GpioPin
*/
void hal_gpio_enable_int_callback(const GpioPin* gpio);
void furi_hal_gpio_enable_int_callback(const GpioPin* gpio);
/**
* Disable interrupt
* @param gpio GpioPin
*/
void hal_gpio_disable_int_callback(const GpioPin* gpio);
void furi_hal_gpio_disable_int_callback(const GpioPin* gpio);
/**
* Remove interrupt
* @param gpio GpioPin
*/
void hal_gpio_remove_int_callback(const GpioPin* gpio);
void furi_hal_gpio_remove_int_callback(const GpioPin* gpio);
/**
* GPIO write pin
* @param gpio GpioPin
* @param state true / false
*/
static inline void hal_gpio_write(const GpioPin* gpio, const bool state) {
static inline void furi_hal_gpio_write(const GpioPin* gpio, const bool state) {
// writing to BSSR is an atomic operation
if(state == true) {
gpio->port->BSRR = gpio->pin;
@@ -240,12 +239,28 @@ static inline void hal_gpio_write(const GpioPin* gpio, const bool state) {
}
}
/**
* GPIO read pin
* @param port GPIO port
* @param pin pin mask
* @return true / false
*/
static inline void
furi_hal_gpio_write_port_pin(GPIO_TypeDef* port, uint16_t pin, const bool state) {
// writing to BSSR is an atomic operation
if(state == true) {
port->BSRR = pin;
} else {
port->BSRR = pin << GPIO_NUMBER;
}
}
/**
* GPIO read pin
* @param gpio GpioPin
* @return true / false
*/
static inline bool hal_gpio_read(const GpioPin* gpio) {
static inline bool furi_hal_gpio_read(const GpioPin* gpio) {
if((gpio->port->IDR & gpio->pin) != 0x00U) {
return true;
} else {
@@ -253,6 +268,20 @@ static inline bool hal_gpio_read(const GpioPin* gpio) {
}
}
/**
* GPIO read pin
* @param port GPIO port
* @param pin pin mask
* @return true / false
*/
static inline bool furi_hal_gpio_read_port_pin(GPIO_TypeDef* port, uint16_t pin) {
if((port->IDR & pin) != 0x00U) {
return true;
} else {
return false;
}
}
#ifdef __cplusplus
}
#endif

View File

@@ -1,4 +1,5 @@
#include <furi_hal_i2c.h>
#include <furi_hal_delay.h>
#include <furi_hal_version.h>
#include <stm32wbxx_ll_i2c.h>
@@ -50,11 +51,11 @@ bool furi_hal_i2c_tx(
furi_assert(timeout > 0);
bool ret = true;
uint32_t timeout_tick = HAL_GetTick() + timeout;
uint32_t timeout_tick = furi_hal_get_tick() + timeout;
do {
while(LL_I2C_IsActiveFlag_BUSY(handle->bus->i2c)) {
if(HAL_GetTick() >= timeout_tick) {
if(furi_hal_get_tick() >= timeout_tick) {
ret = false;
break;
}
@@ -79,7 +80,7 @@ bool furi_hal_i2c_tx(
size--;
}
if(HAL_GetTick() >= timeout_tick) {
if(furi_hal_get_tick() >= timeout_tick) {
ret = false;
break;
}
@@ -101,11 +102,11 @@ bool furi_hal_i2c_rx(
furi_assert(timeout > 0);
bool ret = true;
uint32_t timeout_tick = HAL_GetTick() + timeout;
uint32_t timeout_tick = furi_hal_get_tick() + timeout;
do {
while(LL_I2C_IsActiveFlag_BUSY(handle->bus->i2c)) {
if(HAL_GetTick() >= timeout_tick) {
if(furi_hal_get_tick() >= timeout_tick) {
ret = false;
break;
}
@@ -130,7 +131,7 @@ bool furi_hal_i2c_rx(
size--;
}
if(HAL_GetTick() >= timeout_tick) {
if(furi_hal_get_tick() >= timeout_tick) {
ret = false;
break;
}
@@ -165,11 +166,11 @@ bool furi_hal_i2c_is_device_ready(FuriHalI2cBusHandle* handle, uint8_t i2c_addr,
furi_assert(timeout > 0);
bool ret = true;
uint32_t timeout_tick = HAL_GetTick() + timeout;
uint32_t timeout_tick = furi_hal_get_tick() + timeout;
do {
while(LL_I2C_IsActiveFlag_BUSY(handle->bus->i2c)) {
if(HAL_GetTick() >= timeout_tick) {
if(furi_hal_get_tick() >= timeout_tick) {
return false;
}
}
@@ -180,14 +181,14 @@ bool furi_hal_i2c_is_device_ready(FuriHalI2cBusHandle* handle, uint8_t i2c_addr,
while((!LL_I2C_IsActiveFlag_NACK(handle->bus->i2c)) &&
(!LL_I2C_IsActiveFlag_STOP(handle->bus->i2c))) {
if(HAL_GetTick() >= timeout_tick) {
if(furi_hal_get_tick() >= timeout_tick) {
return false;
}
}
if(LL_I2C_IsActiveFlag_NACK(handle->bus->i2c)) {
while(!LL_I2C_IsActiveFlag_STOP(handle->bus->i2c)) {
if(HAL_GetTick() >= timeout_tick) {
if(furi_hal_get_tick() >= timeout_tick) {
return false;
}
}
@@ -204,7 +205,7 @@ bool furi_hal_i2c_is_device_ready(FuriHalI2cBusHandle* handle, uint8_t i2c_addr,
}
while(!LL_I2C_IsActiveFlag_STOP(handle->bus->i2c)) {
if(HAL_GetTick() >= timeout_tick) {
if(furi_hal_get_tick() >= timeout_tick) {
return false;
}
}
@@ -298,11 +299,11 @@ bool furi_hal_i2c_write_mem(
bool ret = true;
uint8_t size = len + 1;
uint32_t timeout_tick = HAL_GetTick() + timeout;
uint32_t timeout_tick = furi_hal_get_tick() + timeout;
do {
while(LL_I2C_IsActiveFlag_BUSY(handle->bus->i2c)) {
if(HAL_GetTick() >= timeout_tick) {
if(furi_hal_get_tick() >= timeout_tick) {
ret = false;
break;
}
@@ -331,7 +332,7 @@ bool furi_hal_i2c_write_mem(
size--;
}
if(HAL_GetTick() >= timeout_tick) {
if(furi_hal_get_tick() >= timeout_tick) {
ret = false;
break;
}

View File

@@ -1,6 +1,8 @@
#include "furi_hal_i2c_config.h"
#include <furi_hal_resources.h>
#include <furi_hal_version.h>
#include <stm32wbxx_ll_bus.h>
#include <stm32wbxx_ll_rcc.h>
/** Timing register value is computed with the STM32CubeMX Tool,
* Standard Mode @100kHz with I2CCLK = 64 MHz,
@@ -70,13 +72,13 @@ void furi_hal_i2c_bus_handle_power_event(
FuriHalI2cBusHandle* handle,
FuriHalI2cBusHandleEvent event) {
if(event == FuriHalI2cBusHandleEventActivate) {
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_i2c_power_sda,
GpioModeAltFunctionOpenDrain,
GpioPullNo,
GpioSpeedLow,
GpioAltFn4I2C1);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_i2c_power_scl,
GpioModeAltFunctionOpenDrain,
GpioPullNo,
@@ -104,11 +106,11 @@ void furi_hal_i2c_bus_handle_power_event(
LL_I2C_EnableClockStretching(handle->bus->i2c);
} else if(event == FuriHalI2cBusHandleEventDeactivate) {
LL_I2C_Disable(handle->bus->i2c);
hal_gpio_write(&gpio_i2c_power_sda, 1);
hal_gpio_write(&gpio_i2c_power_scl, 1);
hal_gpio_init_ex(
furi_hal_gpio_write(&gpio_i2c_power_sda, 1);
furi_hal_gpio_write(&gpio_i2c_power_scl, 1);
furi_hal_gpio_init_ex(
&gpio_i2c_power_sda, GpioModeAnalog, GpioPullNo, GpioSpeedLow, GpioAltFnUnused);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_i2c_power_scl, GpioModeAnalog, GpioPullNo, GpioSpeedLow, GpioAltFnUnused);
}
}
@@ -122,9 +124,9 @@ void furi_hal_i2c_bus_handle_external_event(
FuriHalI2cBusHandle* handle,
FuriHalI2cBusHandleEvent event) {
if(event == FuriHalI2cBusHandleEventActivate) {
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_ext_pc0, GpioModeAltFunctionOpenDrain, GpioPullNo, GpioSpeedLow, GpioAltFn4I2C3);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_ext_pc1, GpioModeAltFunctionOpenDrain, GpioPullNo, GpioSpeedLow, GpioAltFn4I2C3);
LL_I2C_InitTypeDef I2C_InitStruct = {0};
@@ -144,10 +146,12 @@ void furi_hal_i2c_bus_handle_external_event(
LL_I2C_EnableClockStretching(handle->bus->i2c);
} else if(event == FuriHalI2cBusHandleEventDeactivate) {
LL_I2C_Disable(handle->bus->i2c);
hal_gpio_write(&gpio_ext_pc0, 1);
hal_gpio_write(&gpio_ext_pc1, 1);
hal_gpio_init_ex(&gpio_ext_pc0, GpioModeAnalog, GpioPullNo, GpioSpeedLow, GpioAltFnUnused);
hal_gpio_init_ex(&gpio_ext_pc1, GpioModeAnalog, GpioPullNo, GpioSpeedLow, GpioAltFnUnused);
furi_hal_gpio_write(&gpio_ext_pc0, 1);
furi_hal_gpio_write(&gpio_ext_pc1, 1);
furi_hal_gpio_init_ex(
&gpio_ext_pc0, GpioModeAnalog, GpioPullNo, GpioSpeedLow, GpioAltFnUnused);
furi_hal_gpio_init_ex(
&gpio_ext_pc1, GpioModeAnalog, GpioPullNo, GpioSpeedLow, GpioAltFnUnused);
}
}

View File

@@ -91,45 +91,45 @@ void furi_hal_ibutton_emulate_stop() {
void furi_hal_ibutton_start_drive() {
furi_hal_ibutton_pin_high();
hal_gpio_init(&ibutton_gpio, GpioModeOutputOpenDrain, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&ibutton_gpio, GpioModeOutputOpenDrain, GpioPullNo, GpioSpeedLow);
}
void furi_hal_ibutton_start_drive_in_isr() {
hal_gpio_init(&ibutton_gpio, GpioModeOutputOpenDrain, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&ibutton_gpio, GpioModeOutputOpenDrain, GpioPullNo, GpioSpeedLow);
LL_EXTI_ClearFlag_0_31(ibutton_gpio.pin);
}
void furi_hal_ibutton_start_interrupt() {
furi_hal_ibutton_pin_high();
hal_gpio_init(&ibutton_gpio, GpioModeInterruptRiseFall, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&ibutton_gpio, GpioModeInterruptRiseFall, GpioPullNo, GpioSpeedLow);
}
void furi_hal_ibutton_start_interrupt_in_isr() {
hal_gpio_init(&ibutton_gpio, GpioModeInterruptRiseFall, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&ibutton_gpio, GpioModeInterruptRiseFall, GpioPullNo, GpioSpeedLow);
LL_EXTI_ClearFlag_0_31(ibutton_gpio.pin);
}
void furi_hal_ibutton_stop() {
furi_hal_ibutton_pin_high();
hal_gpio_init(&ibutton_gpio, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&ibutton_gpio, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
}
void furi_hal_ibutton_add_interrupt(GpioExtiCallback cb, void* context) {
hal_gpio_add_int_callback(&ibutton_gpio, cb, context);
furi_hal_gpio_add_int_callback(&ibutton_gpio, cb, context);
}
void furi_hal_ibutton_remove_interrupt() {
hal_gpio_remove_int_callback(&ibutton_gpio);
furi_hal_gpio_remove_int_callback(&ibutton_gpio);
}
void furi_hal_ibutton_pin_low() {
hal_gpio_write(&ibutton_gpio, false);
furi_hal_gpio_write(&ibutton_gpio, false);
}
void furi_hal_ibutton_pin_high() {
hal_gpio_write(&ibutton_gpio, true);
furi_hal_gpio_write(&ibutton_gpio, true);
}
bool furi_hal_ibutton_pin_get_level() {
return hal_gpio_read(&ibutton_gpio);
return furi_hal_gpio_read(&ibutton_gpio);
}

View File

@@ -14,7 +14,6 @@
#include <stdio.h>
#include <furi.h>
#include <math.h>
#include <main.h>
#define INFRARED_TX_DEBUG 0
@@ -138,7 +137,7 @@ static void furi_hal_infrared_tim_rx_isr() {
void furi_hal_infrared_async_rx_start(void) {
furi_assert(furi_hal_infrared_state == InfraredStateIdle);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_infrared_rx, GpioModeAltFunctionPushPull, GpioPullNo, GpioSpeedLow, GpioAltFn1TIM2);
LL_TIM_InitTypeDef TIM_InitStruct = {0};
@@ -548,7 +547,7 @@ static void furi_hal_infrared_async_tx_free_resources(void) {
(furi_hal_infrared_state == InfraredStateAsyncTxStopped));
osStatus_t status;
hal_gpio_init(&gpio_infrared_tx, GpioModeOutputOpenDrain, GpioPullDown, GpioSpeedLow);
furi_hal_gpio_init(&gpio_infrared_tx, GpioModeOutputOpenDrain, GpioPullDown, GpioSpeedLow);
furi_hal_interrupt_set_isr(FuriHalInterruptIdDma1Ch1, NULL, NULL);
furi_hal_interrupt_set_isr(FuriHalInterruptIdDma1Ch2, NULL, NULL);
LL_TIM_DeInit(TIM1);
@@ -604,12 +603,12 @@ void furi_hal_infrared_async_tx_start(uint32_t freq, float duty_cycle) {
LL_TIM_ClearFlag_UPDATE(TIM1);
LL_DMA_EnableChannel(DMA1, LL_DMA_CHANNEL_1);
LL_DMA_EnableChannel(DMA1, LL_DMA_CHANNEL_2);
delay_us(5);
furi_hal_delay_us(5);
LL_TIM_GenerateEvent_UPDATE(TIM1); /* DMA -> TIMx_RCR */
delay_us(5);
furi_hal_delay_us(5);
LL_GPIO_ResetOutputPin(
gpio_infrared_tx.port, gpio_infrared_tx.pin); /* when disable it prevents false pulse */
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_infrared_tx, GpioModeAltFunctionPushPull, GpioPullUp, GpioSpeedHigh, GpioAltFn1TIM1);
FURI_CRITICAL_ENTER();

View File

@@ -1,10 +1,11 @@
#include "furi_hal_interrupt.h"
#include "furi_hal_delay.h"
#include <furi.h>
#include <main.h>
#include <stm32wbxx.h>
#include <stm32wbxx_ll_tim.h>
#include <stm32wbxx_ll_rcc.h>
#define TAG "FuriHalInterrupt"
@@ -80,9 +81,6 @@ void furi_hal_interrupt_init() {
NVIC_SetPriority(PendSV_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 15, 0));
NVIC_SetPriority(HSEM_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
HAL_NVIC_EnableIRQ(HSEM_IRQn);
FURI_LOG_I(TAG, "Init OK");
}
@@ -251,7 +249,7 @@ extern void HW_IPCC_Tx_Handler();
extern void HW_IPCC_Rx_Handler();
void SysTick_Handler(void) {
HAL_IncTick();
furi_hal_tick();
}
void USB_LP_IRQHandler(void) {

View File

@@ -2,6 +2,7 @@
#include <stm32wbxx_ll_lptim.h>
#include <stm32wbxx_ll_bus.h>
#include <stm32wbxx_ll_rcc.h>
#include <stdint.h>
// Timer used for system ticks

View File

@@ -1,6 +1,7 @@
#include <furi_hal_power.h>
#include <furi_hal_clock.h>
#include <furi_hal_bt.h>
#include <furi_hal_resources.h>
#include <stm32wbxx_ll_rcc.h>
#include <stm32wbxx_ll_pwr.h>
@@ -8,7 +9,6 @@
#include <stm32wbxx_ll_cortex.h>
#include <stm32wbxx_ll_gpio.h>
#include <main.h>
#include <hw_conf.h>
#include <bq27220.h>
#include <bq25896.h>

View File

@@ -1,5 +1,4 @@
#include <furi_hal_resources.h>
#include "main.h"
#include <furi.h>
const GpioPin vibro_gpio = {.port = VIBRO_GPIO_Port, .pin = VIBRO_Pin};
@@ -13,8 +12,16 @@ const GpioPin gpio_display_cs = {.port = DISPLAY_CS_GPIO_Port, .pin = DISPLAY_CS
const GpioPin gpio_display_rst = {.port = DISPLAY_RST_GPIO_Port, .pin = DISPLAY_RST_Pin};
const GpioPin gpio_display_di = {.port = DISPLAY_DI_GPIO_Port, .pin = DISPLAY_DI_Pin};
const GpioPin gpio_sdcard_cs = {.port = SD_CS_GPIO_Port, .pin = SD_CS_Pin};
const GpioPin gpio_sdcard_cd = {.port = SD_CD_GPIO_Port, .pin = SD_CD_Pin};
const GpioPin gpio_nfc_cs = {.port = NFC_CS_GPIO_Port, .pin = NFC_CS_Pin};
const GpioPin gpio_button_up = {.port = GPIOB, .pin = LL_GPIO_PIN_10};
const GpioPin gpio_button_down = {.port = GPIOC, .pin = LL_GPIO_PIN_6};
const GpioPin gpio_button_right = {.port = GPIOB, .pin = LL_GPIO_PIN_12};
const GpioPin gpio_button_left = {.port = GPIOB, .pin = LL_GPIO_PIN_11};
const GpioPin gpio_button_ok = {.port = GPIOH, .pin = LL_GPIO_PIN_3};
const GpioPin gpio_button_back = {.port = GPIOC, .pin = LL_GPIO_PIN_13};
const GpioPin gpio_spi_d_miso = {.port = SPI_D_MISO_GPIO_Port, .pin = SPI_D_MISO_Pin};
const GpioPin gpio_spi_d_mosi = {.port = SPI_D_MOSI_GPIO_Port, .pin = SPI_D_MOSI_Pin};
const GpioPin gpio_spi_d_sck = {.port = SPI_D_SCK_GPIO_Port, .pin = SPI_D_SCK_Pin};
@@ -22,14 +29,14 @@ const GpioPin gpio_spi_r_miso = {.port = SPI_R_MISO_GPIO_Port, .pin = SPI_R_MISO
const GpioPin gpio_spi_r_mosi = {.port = SPI_R_MOSI_GPIO_Port, .pin = SPI_R_MOSI_Pin};
const GpioPin gpio_spi_r_sck = {.port = SPI_R_SCK_GPIO_Port, .pin = SPI_R_SCK_Pin};
const GpioPin gpio_ext_pc0 = {.port = GPIOC, .pin = GPIO_PIN_0};
const GpioPin gpio_ext_pc1 = {.port = GPIOC, .pin = GPIO_PIN_1};
const GpioPin gpio_ext_pc3 = {.port = GPIOC, .pin = GPIO_PIN_3};
const GpioPin gpio_ext_pb2 = {.port = GPIOB, .pin = GPIO_PIN_2};
const GpioPin gpio_ext_pb3 = {.port = GPIOB, .pin = GPIO_PIN_3};
const GpioPin gpio_ext_pa4 = {.port = GPIOA, .pin = GPIO_PIN_4};
const GpioPin gpio_ext_pa6 = {.port = GPIOA, .pin = GPIO_PIN_6};
const GpioPin gpio_ext_pa7 = {.port = GPIOA, .pin = GPIO_PIN_7};
const GpioPin gpio_ext_pc0 = {.port = GPIOC, .pin = LL_GPIO_PIN_0};
const GpioPin gpio_ext_pc1 = {.port = GPIOC, .pin = LL_GPIO_PIN_1};
const GpioPin gpio_ext_pc3 = {.port = GPIOC, .pin = LL_GPIO_PIN_3};
const GpioPin gpio_ext_pb2 = {.port = GPIOB, .pin = LL_GPIO_PIN_2};
const GpioPin gpio_ext_pb3 = {.port = GPIOB, .pin = LL_GPIO_PIN_3};
const GpioPin gpio_ext_pa4 = {.port = GPIOA, .pin = LL_GPIO_PIN_4};
const GpioPin gpio_ext_pa6 = {.port = GPIOA, .pin = LL_GPIO_PIN_6};
const GpioPin gpio_ext_pa7 = {.port = GPIOA, .pin = LL_GPIO_PIN_7};
const GpioPin gpio_rfid_pull = {.port = RFID_PULL_GPIO_Port, .pin = RFID_PULL_Pin};
const GpioPin gpio_rfid_carrier_out = {.port = RFID_OUT_GPIO_Port, .pin = RFID_OUT_Pin};
@@ -47,20 +54,75 @@ const GpioPin gpio_i2c_power_scl = {.port = GPIOA, .pin = LL_GPIO_PIN_9};
const GpioPin gpio_speaker = {.port = GPIOB, .pin = LL_GPIO_PIN_8};
const GpioPin gpio_button_up = {.port = GPIOB, .pin = LL_GPIO_PIN_10};
const GpioPin gpio_button_down = {.port = GPIOC, .pin = LL_GPIO_PIN_6};
const GpioPin gpio_button_right = {.port = GPIOB, .pin = LL_GPIO_PIN_12};
const GpioPin gpio_button_left = {.port = GPIOB, .pin = LL_GPIO_PIN_11};
const GpioPin gpio_button_ok = {.port = GPIOH, .pin = LL_GPIO_PIN_3};
const GpioPin gpio_button_back = {.port = GPIOC, .pin = LL_GPIO_PIN_13};
const GpioPin periph_power = {.port = PERIPH_POWER_GPIO_Port, .pin = PERIPH_POWER_Pin};
const InputPin input_pins[] = {
{.pin = &gpio_button_up, .key = InputKeyUp, .inverted = true, .name = "Up"},
{.pin = &gpio_button_down, .key = InputKeyDown, .inverted = true, .name = "Down"},
{.pin = &gpio_button_right, .key = InputKeyRight, .inverted = true, .name = "Right"},
{.pin = &gpio_button_left, .key = InputKeyLeft, .inverted = true, .name = "Left"},
{.pin = &gpio_button_ok, .key = InputKeyOk, .inverted = false, .name = "Ok"},
{.pin = &gpio_button_back, .key = InputKeyBack, .inverted = true, .name = "Back"},
{.gpio = &gpio_button_up, .key = InputKeyUp, .inverted = true, .name = "Up"},
{.gpio = &gpio_button_down, .key = InputKeyDown, .inverted = true, .name = "Down"},
{.gpio = &gpio_button_right, .key = InputKeyRight, .inverted = true, .name = "Right"},
{.gpio = &gpio_button_left, .key = InputKeyLeft, .inverted = true, .name = "Left"},
{.gpio = &gpio_button_ok, .key = InputKeyOk, .inverted = false, .name = "Ok"},
{.gpio = &gpio_button_back, .key = InputKeyBack, .inverted = true, .name = "Back"},
};
const size_t input_pins_count = sizeof(input_pins) / sizeof(InputPin);
void furi_hal_resources_init(void) {
// Button pins
for(size_t i = 0; i < input_pins_count; i++) {
furi_hal_gpio_init(
input_pins[i].gpio, GpioModeInterruptRiseFall, GpioPullUp, GpioSpeedLow);
}
// External header pins
furi_hal_gpio_init(&gpio_ext_pc0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_ext_pc1, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_ext_pc3, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_ext_pb2, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_ext_pb3, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_ext_pa4, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_ext_pa6, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_ext_pa7, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
// Display pins
furi_hal_gpio_init(&gpio_display_rst, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_write(&gpio_display_rst, 0);
furi_hal_gpio_init(&gpio_display_di, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_write(&gpio_display_di, 0);
// SD pins
furi_hal_gpio_init(&gpio_sdcard_cd, GpioModeInput, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_write(&gpio_sdcard_cd, 0);
furi_hal_gpio_init(&vibro_gpio, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&ibutton_gpio, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_rfid_pull, GpioModeInterruptRise, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_rf_sw_0, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&periph_power, GpioModeOutputOpenDrain, GpioPullNo, GpioSpeedLow);
NVIC_SetPriority(EXTI0_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
NVIC_EnableIRQ(EXTI0_IRQn);
NVIC_SetPriority(EXTI1_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
NVIC_EnableIRQ(EXTI1_IRQn);
NVIC_SetPriority(EXTI2_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
NVIC_EnableIRQ(EXTI2_IRQn);
NVIC_SetPriority(EXTI3_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
NVIC_EnableIRQ(EXTI3_IRQn);
NVIC_SetPriority(EXTI4_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
NVIC_EnableIRQ(EXTI4_IRQn);
NVIC_SetPriority(EXTI9_5_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
NVIC_EnableIRQ(EXTI9_5_IRQn);
NVIC_SetPriority(EXTI15_10_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
NVIC_EnableIRQ(EXTI15_10_IRQn);
}

View File

@@ -1,6 +1,5 @@
#pragma once
#include "main.h"
#include <furi.h>
#include <stm32wbxx.h>
@@ -32,12 +31,15 @@ typedef enum {
} Light;
typedef struct {
const GpioPin* pin;
const GpioPin* gpio;
const InputKey key;
const bool inverted;
const char* name;
} InputPin;
extern const InputPin input_pins[];
extern const size_t input_pins_count;
extern const GpioPin vibro_gpio;
extern const GpioPin ibutton_gpio;
@@ -49,6 +51,7 @@ extern const GpioPin gpio_display_cs;
extern const GpioPin gpio_display_rst;
extern const GpioPin gpio_display_di;
extern const GpioPin gpio_sdcard_cs;
extern const GpioPin gpio_sdcard_cd;
extern const GpioPin gpio_nfc_cs;
extern const GpioPin gpio_spi_d_miso;
@@ -82,9 +85,115 @@ extern const GpioPin gpio_i2c_power_scl;
extern const GpioPin gpio_speaker;
// Input pins
extern const InputPin input_pins[];
extern const size_t input_pins_count;
extern const GpioPin periph_power;
#define BUTTON_BACK_GPIO_Port GPIOC
#define BUTTON_BACK_Pin LL_GPIO_PIN_13
#define BUTTON_DOWN_GPIO_Port GPIOC
#define BUTTON_DOWN_Pin LL_GPIO_PIN_6
#define BUTTON_LEFT_GPIO_Port GPIOB
#define BUTTON_LEFT_Pin LL_GPIO_PIN_11
#define BUTTON_OK_GPIO_Port GPIOH
#define BUTTON_OK_Pin LL_GPIO_PIN_3
#define BUTTON_RIGHT_GPIO_Port GPIOB
#define BUTTON_RIGHT_Pin LL_GPIO_PIN_12
#define BUTTON_UP_GPIO_Port GPIOB
#define BUTTON_UP_Pin LL_GPIO_PIN_10
#define CC1101_CS_GPIO_Port GPIOD
#define CC1101_CS_Pin LL_GPIO_PIN_0
#define CC1101_G0_GPIO_Port GPIOA
#define CC1101_G0_Pin LL_GPIO_PIN_1
#define DISPLAY_CS_GPIO_Port GPIOC
#define DISPLAY_CS_Pin LL_GPIO_PIN_11
#define DISPLAY_DI_GPIO_Port GPIOB
#define DISPLAY_DI_Pin LL_GPIO_PIN_1
#define DISPLAY_RST_GPIO_Port GPIOB
#define DISPLAY_RST_Pin LL_GPIO_PIN_0
#define IR_RX_GPIO_Port GPIOA
#define IR_RX_Pin LL_GPIO_PIN_0
#define IR_TX_GPIO_Port GPIOB
#define IR_TX_Pin LL_GPIO_PIN_9
#define NFC_CS_GPIO_Port GPIOE
#define NFC_CS_Pin LL_GPIO_PIN_4
#define PA4_GPIO_Port GPIOA
#define PA4_Pin LL_GPIO_PIN_4
#define PA6_GPIO_Port GPIOA
#define PA6_Pin LL_GPIO_PIN_6
#define PA7_GPIO_Port GPIOA
#define PA7_Pin LL_GPIO_PIN_7
#define PB2_GPIO_Port GPIOB
#define PB2_Pin LL_GPIO_PIN_2
#define PB3_GPIO_Port GPIOB
#define PB3_Pin LL_GPIO_PIN_3
#define PC0_GPIO_Port GPIOC
#define PC0_Pin LL_GPIO_PIN_0
#define PC1_GPIO_Port GPIOC
#define PC1_Pin LL_GPIO_PIN_1
#define PC3_GPIO_Port GPIOC
#define PC3_Pin LL_GPIO_PIN_3
#define PERIPH_POWER_GPIO_Port GPIOA
#define PERIPH_POWER_Pin LL_GPIO_PIN_3
#define QUARTZ_32MHZ_IN_GPIO_Port GPIOC
#define QUARTZ_32MHZ_IN_Pin LL_GPIO_PIN_14
#define QUARTZ_32MHZ_OUT_GPIO_Port GPIOC
#define QUARTZ_32MHZ_OUT_Pin LL_GPIO_PIN_15
#define RFID_OUT_GPIO_Port GPIOB
#define RFID_OUT_Pin LL_GPIO_PIN_13
#define RFID_PULL_GPIO_Port GPIOA
#define RFID_PULL_Pin LL_GPIO_PIN_2
#define RFID_RF_IN_GPIO_Port GPIOC
#define RFID_RF_IN_Pin LL_GPIO_PIN_5
#define RFID_CARRIER_GPIO_Port GPIOA
#define RFID_CARRIER_Pin LL_GPIO_PIN_15
#define RF_SW_0_GPIO_Port GPIOC
#define RF_SW_0_Pin LL_GPIO_PIN_4
#define SD_CD_GPIO_Port GPIOC
#define SD_CD_Pin LL_GPIO_PIN_10
#define SD_CS_GPIO_Port GPIOC
#define SD_CS_Pin LL_GPIO_PIN_12
#define SPEAKER_GPIO_Port GPIOB
#define SPEAKER_Pin LL_GPIO_PIN_8
#define VIBRO_GPIO_Port GPIOA
#define VIBRO_Pin LL_GPIO_PIN_8
#define iBTN_GPIO_Port GPIOB
#define iBTN_Pin LL_GPIO_PIN_14
#define USART1_TX_Pin LL_GPIO_PIN_6
#define USART1_TX_Port GPIOB
#define USART1_RX_Pin LL_GPIO_PIN_7
#define USART1_RX_Port GPIOB
#define SPI_D_MISO_GPIO_Port GPIOC
#define SPI_D_MISO_Pin LL_GPIO_PIN_2
#define SPI_D_MOSI_GPIO_Port GPIOB
#define SPI_D_MOSI_Pin LL_GPIO_PIN_15
#define SPI_D_SCK_GPIO_Port GPIOD
#define SPI_D_SCK_Pin LL_GPIO_PIN_1
#define SPI_R_MISO_GPIO_Port GPIOB
#define SPI_R_MISO_Pin LL_GPIO_PIN_4
#define SPI_R_MOSI_GPIO_Port GPIOB
#define SPI_R_MOSI_Pin LL_GPIO_PIN_5
#define SPI_R_SCK_GPIO_Port GPIOA
#define SPI_R_SCK_Pin LL_GPIO_PIN_5
#define NFC_IRQ_Pin RFID_PULL_Pin
#define NFC_IRQ_GPIO_Port RFID_PULL_GPIO_Port
void furi_hal_resources_init(void);
#ifdef __cplusplus
}

View File

@@ -65,16 +65,16 @@ void furi_hal_rfid_pins_reset() {
furi_hal_ibutton_stop();
// pulldown rfid antenna
hal_gpio_init(&gpio_rfid_carrier_out, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
hal_gpio_write(&gpio_rfid_carrier_out, false);
furi_hal_gpio_init(&gpio_rfid_carrier_out, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_write(&gpio_rfid_carrier_out, false);
// from both sides
hal_gpio_init(&gpio_rfid_pull, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
hal_gpio_write(&gpio_rfid_pull, true);
furi_hal_gpio_init(&gpio_rfid_pull, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_write(&gpio_rfid_pull, true);
hal_gpio_init_simple(&gpio_rfid_carrier, GpioModeAnalog);
furi_hal_gpio_init_simple(&gpio_rfid_carrier, GpioModeAnalog);
hal_gpio_init(&gpio_rfid_data_in, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_rfid_data_in, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
}
void furi_hal_rfid_pins_emulate() {
@@ -83,14 +83,14 @@ void furi_hal_rfid_pins_emulate() {
furi_hal_ibutton_pin_low();
// pull pin to timer out
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_rfid_pull, GpioModeAltFunctionPushPull, GpioPullNo, GpioSpeedLow, GpioAltFn1TIM2);
// pull rfid antenna from carrier side
hal_gpio_init(&gpio_rfid_carrier_out, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
hal_gpio_write(&gpio_rfid_carrier_out, false);
furi_hal_gpio_init(&gpio_rfid_carrier_out, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_write(&gpio_rfid_carrier_out, false);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_rfid_carrier, GpioModeAltFunctionPushPull, GpioPullNo, GpioSpeedLow, GpioAltFn2TIM2);
}
@@ -100,11 +100,11 @@ void furi_hal_rfid_pins_read() {
furi_hal_ibutton_pin_low();
// dont pull rfid antenna
hal_gpio_init(&gpio_rfid_pull, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
hal_gpio_write(&gpio_rfid_pull, false);
furi_hal_gpio_init(&gpio_rfid_pull, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_write(&gpio_rfid_pull, false);
// carrier pin to timer out
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_rfid_carrier_out,
GpioModeAltFunctionPushPull,
GpioPullNo,
@@ -112,15 +112,15 @@ void furi_hal_rfid_pins_read() {
GpioAltFn1TIM1);
// comparator in
hal_gpio_init(&gpio_rfid_data_in, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_rfid_data_in, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
}
void furi_hal_rfid_pin_pull_release() {
hal_gpio_write(&gpio_rfid_pull, true);
furi_hal_gpio_write(&gpio_rfid_pull, true);
}
void furi_hal_rfid_pin_pull_pulldown() {
hal_gpio_write(&gpio_rfid_pull, false);
furi_hal_gpio_write(&gpio_rfid_pull, false);
}
void furi_hal_rfid_tim_read(float freq, float duty_cycle) {

View File

@@ -1,6 +1,7 @@
#include "furi_hal_sd.h"
#include <stm32wbxx_ll_gpio.h>
#include <furi.h>
#include <furi_hal.h>
void hal_sd_detect_init(void) {
// low speed input with pullup

View File

@@ -16,7 +16,7 @@ void furi_hal_speaker_init() {
LL_TIM_DeInit(FURI_HAL_SPEAKER_TIMER);
FURI_CRITICAL_EXIT();
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_speaker, GpioModeAltFunctionPushPull, GpioPullNo, GpioSpeedLow, GpioAltFn14TIM16);
}

View File

@@ -139,42 +139,42 @@ inline static void furi_hal_spi_bus_r_handle_event_callback(
FuriHalSpiBusHandleEvent event,
const LL_SPI_InitTypeDef* preset) {
if(event == FuriHalSpiBusHandleEventInit) {
hal_gpio_write(handle->cs, true);
hal_gpio_init(handle->cs, GpioModeOutputPushPull, GpioPullNo, GpioSpeedVeryHigh);
furi_hal_gpio_write(handle->cs, true);
furi_hal_gpio_init(handle->cs, GpioModeOutputPushPull, GpioPullNo, GpioSpeedVeryHigh);
} else if(event == FuriHalSpiBusHandleEventDeinit) {
hal_gpio_write(handle->cs, true);
hal_gpio_init(handle->cs, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_write(handle->cs, true);
furi_hal_gpio_init(handle->cs, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
} else if(event == FuriHalSpiBusHandleEventActivate) {
LL_SPI_Init(handle->bus->spi, (LL_SPI_InitTypeDef*)preset);
LL_SPI_SetRxFIFOThreshold(handle->bus->spi, LL_SPI_RX_FIFO_TH_QUARTER);
LL_SPI_Enable(handle->bus->spi);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
handle->miso,
GpioModeAltFunctionPushPull,
GpioPullNo,
GpioSpeedVeryHigh,
GpioAltFn5SPI1);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
handle->mosi,
GpioModeAltFunctionPushPull,
GpioPullNo,
GpioSpeedVeryHigh,
GpioAltFn5SPI1);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
handle->sck,
GpioModeAltFunctionPushPull,
GpioPullNo,
GpioSpeedVeryHigh,
GpioAltFn5SPI1);
hal_gpio_write(handle->cs, false);
furi_hal_gpio_write(handle->cs, false);
} else if(event == FuriHalSpiBusHandleEventDeactivate) {
hal_gpio_write(handle->cs, true);
furi_hal_gpio_write(handle->cs, true);
hal_gpio_init(handle->miso, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
hal_gpio_init(handle->mosi, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
hal_gpio_init(handle->sck, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(handle->miso, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(handle->mosi, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(handle->sck, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
LL_SPI_Disable(handle->bus->spi);
}
@@ -230,22 +230,22 @@ inline static void furi_hal_spi_bus_d_handle_event_callback(
FuriHalSpiBusHandleEvent event,
const LL_SPI_InitTypeDef* preset) {
if(event == FuriHalSpiBusHandleEventInit) {
hal_gpio_write(handle->cs, true);
hal_gpio_init(handle->cs, GpioModeOutputPushPull, GpioPullUp, GpioSpeedVeryHigh);
furi_hal_gpio_write(handle->cs, true);
furi_hal_gpio_init(handle->cs, GpioModeOutputPushPull, GpioPullUp, GpioSpeedVeryHigh);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
handle->miso,
GpioModeAltFunctionPushPull,
GpioPullNo,
GpioSpeedVeryHigh,
GpioAltFn5SPI2);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
handle->mosi,
GpioModeAltFunctionPushPull,
GpioPullNo,
GpioSpeedVeryHigh,
GpioAltFn5SPI2);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
handle->sck,
GpioModeAltFunctionPushPull,
GpioPullNo,
@@ -253,15 +253,15 @@ inline static void furi_hal_spi_bus_d_handle_event_callback(
GpioAltFn5SPI2);
} else if(event == FuriHalSpiBusHandleEventDeinit) {
hal_gpio_write(handle->cs, true);
hal_gpio_init(handle->cs, GpioModeAnalog, GpioPullUp, GpioSpeedLow);
furi_hal_gpio_write(handle->cs, true);
furi_hal_gpio_init(handle->cs, GpioModeAnalog, GpioPullUp, GpioSpeedLow);
} else if(event == FuriHalSpiBusHandleEventActivate) {
LL_SPI_Init(handle->bus->spi, (LL_SPI_InitTypeDef*)preset);
LL_SPI_SetRxFIFOThreshold(handle->bus->spi, LL_SPI_RX_FIFO_TH_QUARTER);
LL_SPI_Enable(handle->bus->spi);
hal_gpio_write(handle->cs, false);
furi_hal_gpio_write(handle->cs, false);
} else if(event == FuriHalSpiBusHandleEventDeactivate) {
hal_gpio_write(handle->cs, true);
furi_hal_gpio_write(handle->cs, true);
LL_SPI_Disable(handle->bus->spi);
}
}

View File

@@ -7,6 +7,8 @@
#include <furi_hal_interrupt.h>
#include <furi_hal_resources.h>
#include <stm32wbxx_ll_dma.h>
#include <furi.h>
#include <cc1101.h>
#include <stdio.h>
@@ -328,34 +330,34 @@ void furi_hal_subghz_init() {
furi_hal_spi_acquire(&furi_hal_spi_bus_handle_subghz);
#ifdef FURI_HAL_SUBGHZ_TX_GPIO
hal_gpio_init(&FURI_HAL_SUBGHZ_TX_GPIO, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&FURI_HAL_SUBGHZ_TX_GPIO, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
#endif
// Reset
hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
cc1101_reset(&furi_hal_spi_bus_handle_subghz);
cc1101_write_reg(&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG0, CC1101IocfgHighImpedance);
// Prepare GD0 for power on self test
hal_gpio_init(&gpio_cc1101_g0, GpioModeInput, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_cc1101_g0, GpioModeInput, GpioPullNo, GpioSpeedLow);
// GD0 low
cc1101_write_reg(&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG0, CC1101IocfgHW);
while(hal_gpio_read(&gpio_cc1101_g0) != false)
while(furi_hal_gpio_read(&gpio_cc1101_g0) != false)
;
// GD0 high
cc1101_write_reg(
&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG0, CC1101IocfgHW | CC1101_IOCFG_INV);
while(hal_gpio_read(&gpio_cc1101_g0) != true)
while(furi_hal_gpio_read(&gpio_cc1101_g0) != true)
;
// Reset GD0 to floating state
cc1101_write_reg(&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG0, CC1101IocfgHighImpedance);
hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
// RF switches
hal_gpio_init(&gpio_rf_sw_0, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_rf_sw_0, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
cc1101_write_reg(&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG2, CC1101IocfgHW);
// Go to sleep
@@ -372,7 +374,7 @@ void furi_hal_subghz_sleep() {
cc1101_switch_to_idle(&furi_hal_spi_bus_handle_subghz);
cc1101_write_reg(&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG0, CC1101IocfgHighImpedance);
hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
cc1101_shutdown(&furi_hal_spi_bus_handle_subghz);
@@ -493,7 +495,7 @@ void furi_hal_subghz_shutdown() {
void furi_hal_subghz_reset() {
furi_hal_spi_acquire(&furi_hal_spi_bus_handle_subghz);
hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
cc1101_switch_to_idle(&furi_hal_spi_bus_handle_subghz);
cc1101_reset(&furi_hal_spi_bus_handle_subghz);
cc1101_write_reg(&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG0, CC1101IocfgHighImpedance);
@@ -634,18 +636,18 @@ uint32_t furi_hal_subghz_set_frequency(uint32_t value) {
void furi_hal_subghz_set_path(FuriHalSubGhzPath path) {
furi_hal_spi_acquire(&furi_hal_spi_bus_handle_subghz);
if(path == FuriHalSubGhzPath433) {
hal_gpio_write(&gpio_rf_sw_0, 0);
furi_hal_gpio_write(&gpio_rf_sw_0, 0);
cc1101_write_reg(
&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG2, CC1101IocfgHW | CC1101_IOCFG_INV);
} else if(path == FuriHalSubGhzPath315) {
hal_gpio_write(&gpio_rf_sw_0, 1);
furi_hal_gpio_write(&gpio_rf_sw_0, 1);
cc1101_write_reg(&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG2, CC1101IocfgHW);
} else if(path == FuriHalSubGhzPath868) {
hal_gpio_write(&gpio_rf_sw_0, 1);
furi_hal_gpio_write(&gpio_rf_sw_0, 1);
cc1101_write_reg(
&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG2, CC1101IocfgHW | CC1101_IOCFG_INV);
} else if(path == FuriHalSubGhzPathIsolate) {
hal_gpio_write(&gpio_rf_sw_0, 0);
furi_hal_gpio_write(&gpio_rf_sw_0, 0);
cc1101_write_reg(&furi_hal_spi_bus_handle_subghz, CC1101_IOCFG2, CC1101IocfgHW);
} else {
furi_crash(NULL);
@@ -688,7 +690,7 @@ void furi_hal_subghz_start_async_rx(FuriHalSubGhzCaptureCallback callback, void*
furi_hal_subghz_capture_callback = callback;
furi_hal_subghz_capture_callback_context = context;
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_cc1101_g0, GpioModeAltFunctionPushPull, GpioPullNo, GpioSpeedLow, GpioAltFn1TIM2);
// Timer: base
@@ -750,7 +752,7 @@ void furi_hal_subghz_stop_async_rx() {
FURI_CRITICAL_EXIT();
furi_hal_interrupt_set_isr(FuriHalInterruptIdTIM2, NULL, NULL);
hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
}
#define API_HAL_SUBGHZ_ASYNC_TX_BUFFER_FULL (256)
@@ -838,7 +840,7 @@ static void furi_hal_subghz_async_tx_timer_isr() {
if(furi_hal_subghz_state == SubGhzStateAsyncTx) {
furi_hal_subghz_state = SubGhzStateAsyncTxLast;
//forcibly pulls the pin to the ground so that there is no carrier
hal_gpio_init(&gpio_cc1101_g0, GpioModeInput, GpioPullDown, GpioSpeedLow);
furi_hal_gpio_init(&gpio_cc1101_g0, GpioModeInput, GpioPullDown, GpioSpeedLow);
} else {
furi_hal_subghz_state = SubGhzStateAsyncTxEnd;
LL_TIM_DisableCounter(TIM2);
@@ -868,7 +870,7 @@ bool furi_hal_subghz_start_async_tx(FuriHalSubGhzAsyncTxCallback callback, void*
furi_hal_subghz_async_tx.buffer, API_HAL_SUBGHZ_ASYNC_TX_BUFFER_FULL);
// Connect CC1101_GD0 to TIM2 as output
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_cc1101_g0, GpioModeAltFunctionPushPull, GpioPullDown, GpioSpeedLow, GpioAltFn1TIM2);
// Configure DMA
@@ -920,7 +922,7 @@ bool furi_hal_subghz_start_async_tx(FuriHalSubGhzAsyncTxCallback callback, void*
// Start counter
LL_TIM_GenerateEvent_UPDATE(TIM2);
#ifdef FURI_HAL_SUBGHZ_TX_GPIO
hal_gpio_write(&FURI_HAL_SUBGHZ_TX_GPIO, true);
furi_hal_gpio_write(&FURI_HAL_SUBGHZ_TX_GPIO, true);
#endif
furi_hal_subghz_tx();
@@ -942,7 +944,7 @@ void furi_hal_subghz_stop_async_tx() {
// Shutdown radio
furi_hal_subghz_idle();
#ifdef FURI_HAL_SUBGHZ_TX_GPIO
hal_gpio_write(&FURI_HAL_SUBGHZ_TX_GPIO, false);
furi_hal_gpio_write(&FURI_HAL_SUBGHZ_TX_GPIO, false);
#endif
// Deinitialize Timer
@@ -956,7 +958,7 @@ void furi_hal_subghz_stop_async_tx() {
furi_hal_interrupt_set_isr(FuriHalInterruptIdDma1Ch1, NULL, NULL);
// Deinitialize GPIO
hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_cc1101_g0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
FURI_CRITICAL_EXIT();
free(furi_hal_subghz_async_tx.buffer);

View File

@@ -2,6 +2,7 @@
#include <stdbool.h>
#include <stm32wbxx_ll_lpuart.h>
#include <stm32wbxx_ll_usart.h>
#include <stm32wbxx_ll_rcc.h>
#include <furi_hal_resources.h>
#include <furi.h>
@@ -11,13 +12,13 @@ static void (*irq_cb[2])(uint8_t ev, uint8_t data, void* context);
static void* irq_ctx[2];
static void furi_hal_usart_init(uint32_t baud) {
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_usart_tx,
GpioModeAltFunctionPushPull,
GpioPullUp,
GpioSpeedVeryHigh,
GpioAltFn7USART1);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_usart_rx,
GpioModeAltFunctionPushPull,
GpioPullUp,
@@ -44,17 +45,17 @@ static void furi_hal_usart_init(uint32_t baud) {
LL_USART_EnableIT_RXNE_RXFNE(USART1);
LL_USART_EnableIT_IDLE(USART1);
HAL_NVIC_SetPriority(USART1_IRQn, 5, 0);
NVIC_SetPriority(USART1_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
}
static void furi_hal_lpuart_init(uint32_t baud) {
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_ext_pc0,
GpioModeAltFunctionPushPull,
GpioPullUp,
GpioSpeedVeryHigh,
GpioAltFn8LPUART1);
hal_gpio_init_ex(
furi_hal_gpio_init_ex(
&gpio_ext_pc1,
GpioModeAltFunctionPushPull,
GpioPullUp,
@@ -81,7 +82,7 @@ static void furi_hal_lpuart_init(uint32_t baud) {
LL_LPUART_EnableIT_RXNE_RXFNE(LPUART1);
LL_LPUART_EnableIT_IDLE(LPUART1);
HAL_NVIC_SetPriority(LPUART1_IRQn, 5, 0);
NVIC_SetPriority(LPUART1_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
}
void furi_hal_uart_init(FuriHalUartId ch, uint32_t baud) {
@@ -126,12 +127,12 @@ void furi_hal_uart_deinit(FuriHalUartId ch) {
furi_hal_uart_set_irq_cb(ch, NULL, NULL);
if(ch == FuriHalUartIdUSART1) {
LL_USART_Disable(USART1);
hal_gpio_init(&gpio_usart_tx, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
hal_gpio_init(&gpio_usart_rx, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_usart_tx, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_usart_rx, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
} else if(ch == FuriHalUartIdLPUART1) {
LL_LPUART_Disable(LPUART1);
hal_gpio_init(&gpio_ext_pc0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
hal_gpio_init(&gpio_ext_pc1, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_ext_pc0, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_init(&gpio_ext_pc1, GpioModeAnalog, GpioPullNo, GpioSpeedLow);
}
}

View File

@@ -3,6 +3,7 @@
#include "furi_hal_usb.h"
#include "furi_hal_vcp.h"
#include <furi_hal_power.h>
#include <stm32wbxx_ll_pwr.h>
#include <furi.h>
#include "usb.h"
@@ -75,7 +76,7 @@ void furi_hal_usb_init(void) {
usb.enabled = false;
usb.if_cur = NULL;
HAL_NVIC_SetPriority(USB_LP_IRQn, 5, 0);
NVIC_SetPriority(USB_LP_IRQn, NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 5, 0));
NVIC_EnableIRQ(USB_LP_IRQn);
usb.thread = furi_thread_alloc();

View File

@@ -4,11 +4,11 @@
#define TAG "FuriHalVibro"
void furi_hal_vibro_init() {
hal_gpio_init(&vibro_gpio, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
hal_gpio_write(&vibro_gpio, false);
furi_hal_gpio_init(&vibro_gpio, GpioModeOutputPushPull, GpioPullNo, GpioSpeedLow);
furi_hal_gpio_write(&vibro_gpio, false);
FURI_LOG_I(TAG, "Init OK");
}
void furi_hal_vibro_on(bool value) {
hal_gpio_write(&vibro_gpio, value);
furi_hal_gpio_write(&vibro_gpio, value);
}

View File

@@ -41,25 +41,13 @@ ASM_SOURCES += $(MXPROJECT_DIR)/startup_stm32wb55xx_cm4.s
CUBE_DIR = ../lib/STM32CubeWB
CFLAGS += \
-DUSE_FULL_LL_DRIVER \
-DUSE_HAL_DRIVER \
-DHAVE_FREERTOS
CFLAGS += \
-I$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Inc \
-I$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Inc/Legacy \
-I$(CUBE_DIR)/Drivers/CMSIS/Device/ST \
-I$(CUBE_DIR)/Drivers/CMSIS/Device/ST/STM32WBxx/Include \
-I$(CUBE_DIR)/Drivers/CMSIS/Include
C_SOURCES += \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_cortex.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_cryp.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_exti.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_gpio.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pcd_ex.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_pwr_ex.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rcc.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_adc.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_comp.c \
$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_dma.c \

View File

@@ -5,7 +5,7 @@
#pragma once
#include "main.h"
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
@@ -17,26 +17,31 @@ extern uint32_t instructions_per_us;
*/
void furi_hal_delay_init(void);
/** Increase tick counter.
* Should be called from SysTick ISR
*/
void furi_hal_tick(void);
/** Get current tick counter
*
* System uptime, may overflow.
*
* @return Current ticks in milliseconds
*/
uint32_t furi_hal_get_tick(void);
/** Delay in milliseconds
* @warning Cannot be used from ISR
*
* @param[in] milliseconds milliseconds to wait
*/
void delay(float milliseconds);
void furi_hal_delay_ms(float milliseconds);
/** Delay in microseconds
*
* @param[in] microseconds microseconds to wait
*/
void delay_us(float microseconds);
/** Get current millisecond
*
* System uptime, pProvided by HAL, may overflow.
*
* @return Current milliseconds
*/
uint32_t millis(void);
void furi_hal_delay_us(float microseconds);
#ifdef __cplusplus
}

View File

@@ -7,7 +7,6 @@
#include <stdint.h>
#include <stdbool.h>
#include <main.h>
#ifdef __cplusplus
extern "C" {

View File

@@ -7,7 +7,6 @@
#include <stdint.h>
#include <stdbool.h>
#include <main.h>
#ifdef __cplusplus
extern "C" {