[FL-2263] Flasher service & RAM exec (#1006)

* WIP on stripping fw
* Compact FW build - use RAM_EXEC=1 COMPACT=1 DEBUG=0
* Fixed uninitialized storage struct; small fixes to compact fw
* Flasher srv w/mocked flash ops
* Fixed typos & accomodated FFF changes
* Alternative fw startup branch
* Working load & jmp to RAM fw
* +manifest processing for stage loader; + crc verification for stage payload
* Fixed questionable code & potential leaks
* Lowered screen update rate; added radio stack update stubs; working dfu write
* Console EP with manifest & stage validation
* Added microtar lib; minor ui fixes for updater
* Removed microtar
* Removed mtar #2
* Added a better version of microtar
* TAR archive api; LFS backup & restore core
* Recursive backup/restore
* LFS worker thread
* Added system apps to loader - not visible in UI; full update process with restarts
* Typo fix
* Dropped BL & f6; tooling for updater WIP
* Minor py fixes
* Minor fixes to make it build after merge
* Ported flash workaround from BL + fixed visuals
* Minor cleanup
* Chmod + loader app search fix
* Python linter fix
* Removed usb stuff & float read support for staged loader == -10% of binary size
* Added backup/restore & update pb requests
* Added stub impl to RPC for backup/restore/update commands
* Reworked TAR to use borrowed Storage api; slightly reduced build size by removing `static string`; hidden update-related RPC behind defines
* Moved backup&restore to storage
* Fixed new message types
* Backup/restore/update RPC impl
* Moved furi_hal_crc to LL; minor fixes
* CRC HAL rework to LL
* Purging STM HAL
* Brought back minimal DFU boot mode (no gui); additional crc state checks
* Added splash screen, BROKEN usb function
* Clock init rework WIP
* Stripped graphics from DFU mode
* Temp fix for unused static fun
* WIP update picker - broken!
* Fixed UI
* Bumping version
* Fixed RTC setup
* Backup to update folder instead of ext root
* Removed unused scenes & more usb remnants from staged loader
* CI updates
* Fixed update bundle name
* Temporary restored USB handler
* Attempt to prevent .text corruption
* Comments on how I spent this Saturday
* Added update file icon
* Documentation updates
* Moved common code to lib folder
* Storage: more unit tests
* Storage: blocking dir open, differentiate file and dir when freed.
* Major refactoring; added input processing to updater to allow retrying on failures (not very useful prob). Added API for extraction of thread return value
* Removed re-init check for manifest
* Changed low-level path manipulation to toolbox/path.h; makefile cleanup; tiny fix in lint.py
* Increased update worker stack size
* Text fixes in backup CLI
* Displaying number of update stages to run; removed timeout in handling errors
* Bumping version
* Added thread cleanup for spawner thread
* Updated build targets to exclude firmware bundle from 'ALL'
* Fixed makefile for update_package; skipping VCP init for update mode (ugly)
* Switched github build from ALL to update_package
* Added +x for dist_update.sh
* Cli: add total heap size to "free" command
* Moved (RAM) suffix to build version instead of git commit no.
* DFU comment
* Some fixes suggested by clang-tidy
* Fixed recursive PREFIX macro
* Makefile: gather all new rules in updater namespace. FuriHal: rename bootloader to boot, isr safe delays
* Github: correct build target name in firmware build
* FuriHal: move target switch to boot
* Makefile: fix firmware flash
* Furi, FuriHal: move kernel start to furi, early init
* Drop bootloader related stuff
* Drop cube. Drop bootloader linker script.
* Renamed update_hl, moved constants to #defines
* Moved update-related boot mode to separate bitfield
* Reworked updater cli to single entry point; fixed crash on tar cleanup
* Added Python replacement for dist shell scripts
* Linter fixes for dist.py +x
* Fixes for environment suffix
* Dropped bash scripts
* Added dirty build flag to version structure & interfaces
* Version string escapes
* Fixed flag logic in dist.py; added support for App instances being imported and not terminating the whole program
* Fixed fw address in ReadMe.md
* Rpc: fix crash on double screen start
* Return back original boot behavior and fix jump to system bootloader
* Cleanup code, add error sequence for RTC
* Update firmware readme
* FuriHal: drop boot, restructure RTC registers usage and add header register check
* Furi goes first
* Toolchain: add ccache support
* Renamed update bundle dir

Co-authored-by: DrZlo13 <who.just.the.doctor@gmail.com>
Co-authored-by: あく <alleteam@gmail.com>
This commit is contained in:
hedger
2022-04-13 23:50:25 +03:00
committed by GitHub
parent a25552eb99
commit e02040107b
221 changed files with 4199 additions and 11704 deletions

View File

@@ -6,15 +6,43 @@
#define TAG "FuriHal"
void furi_hal_init() {
furi_hal_rtc_init();
furi_hal_interrupt_init();
void furi_hal_init_early() {
furi_hal_clock_init_early();
furi_hal_delay_init();
furi_hal_resources_init_early();
furi_hal_spi_init_early();
furi_hal_i2c_init_early();
furi_hal_light_init();
furi_hal_rtc_init_early();
}
void furi_hal_deinit_early() {
furi_hal_rtc_deinit_early();
furi_hal_i2c_deinit_early();
furi_hal_spi_deinit_early();
furi_hal_resources_deinit_early();
furi_hal_clock_deinit_early();
}
void furi_hal_init() {
furi_hal_clock_init();
furi_hal_console_init();
furi_hal_rtc_init();
furi_hal_interrupt_init();
furi_hal_flash_init();
furi_hal_resources_init();
FURI_LOG_I(TAG, "GPIO OK");
furi_hal_bootloader_init();
furi_hal_version_init();
furi_hal_spi_init();
@@ -25,21 +53,26 @@ void furi_hal_init() {
FURI_LOG_I(TAG, "Speaker OK");
furi_hal_crypto_init();
furi_hal_crc_init(true);
// VCP + USB
#ifndef FURI_RAM_EXEC
furi_hal_usb_init();
furi_hal_vcp_init();
FURI_LOG_I(TAG, "USB OK");
#endif
furi_hal_i2c_init();
// High Level
furi_hal_power_init();
furi_hal_light_init();
#ifndef FURI_RAM_EXEC
furi_hal_vibro_init();
furi_hal_subghz_init();
furi_hal_nfc_init();
furi_hal_rfid_init();
#endif
furi_hal_bt_init();
furi_hal_compress_icon_init();
@@ -62,7 +95,13 @@ void furi_hal_init() {
LL_MPU_Enable(LL_MPU_CTRL_PRIVILEGED_DEFAULT);
}
void furi_hal_init_critical() {
furi_hal_clock_init();
furi_hal_console_init();
void furi_hal_switch(void* address) {
__set_BASEPRI(0);
asm volatile("ldr r3, [%0] \n"
"msr msp, r3 \n"
"ldr r3, [%1] \n"
"mov pc, r3 \n"
:
: "r"(address), "r"(address + 0x4)
: "r3");
}

View File

@@ -1,25 +0,0 @@
#include <furi_hal_bootloader.h>
#include <furi_hal_rtc.h>
#include <furi.h>
#define TAG "FuriHalBoot"
// Boot request enum
#define BOOT_REQUEST_TAINTED 0x00000000
#define BOOT_REQUEST_CLEAN 0xDADEDADE
#define BOOT_REQUEST_DFU 0xDF00B000
void furi_hal_bootloader_init() {
#ifndef DEBUG
furi_hal_rtc_set_register(FuriHalRtcRegisterBoot, BOOT_REQUEST_TAINTED);
#endif
FURI_LOG_I(TAG, "Init OK");
}
void furi_hal_bootloader_set_mode(FuriHalBootloaderMode mode) {
if(mode == FuriHalBootloaderModeNormal) {
furi_hal_rtc_set_register(FuriHalRtcRegisterBoot, BOOT_REQUEST_CLEAN);
} else if(mode == FuriHalBootloaderModeDFU) {
furi_hal_rtc_set_register(FuriHalRtcRegisterBoot, BOOT_REQUEST_DFU);
}
}

View File

@@ -13,6 +13,39 @@
#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())
void furi_hal_clock_init_early() {
LL_Init1msTick(4000000);
LL_SetSystemCoreClock(4000000);
LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOA);
LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOB);
LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOC);
LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOD);
LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOE);
LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOH);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_SPI1);
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_SPI2);
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_I2C1);
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_I2C3);
}
void furi_hal_clock_deinit_early() {
LL_APB1_GRP1_DisableClock(LL_APB1_GRP1_PERIPH_I2C1);
LL_APB1_GRP1_DisableClock(LL_APB1_GRP1_PERIPH_I2C3);
LL_APB2_GRP1_DisableClock(LL_APB2_GRP1_PERIPH_SPI1);
LL_APB1_GRP1_DisableClock(LL_APB1_GRP1_PERIPH_SPI2);
LL_AHB2_GRP1_DisableClock(LL_AHB2_GRP1_PERIPH_GPIOA);
LL_AHB2_GRP1_DisableClock(LL_AHB2_GRP1_PERIPH_GPIOB);
LL_AHB2_GRP1_DisableClock(LL_AHB2_GRP1_PERIPH_GPIOC);
LL_AHB2_GRP1_DisableClock(LL_AHB2_GRP1_PERIPH_GPIOD);
LL_AHB2_GRP1_DisableClock(LL_AHB2_GRP1_PERIPH_GPIOE);
LL_AHB2_GRP1_DisableClock(LL_AHB2_GRP1_PERIPH_GPIOH);
}
void furi_hal_clock_init() {
/* Prepare Flash memory for 64mHz system clock */
LL_FLASH_SetLatency(LL_FLASH_LATENCY_3);

View File

@@ -1,5 +1,11 @@
#pragma once
/** Early initialization */
void furi_hal_clock_init_early();
/** Early deinitialization */
void furi_hal_clock_deinit_early();
/** Initialize clocks */
void furi_hal_clock_init();

View File

@@ -0,0 +1,88 @@
#include <furi_hal.h>
#include <stm32wbxx_ll_crc.h>
typedef enum {
CRC_State_Reset,
CRC_State_Ready,
CRC_State_Busy,
} CRC_State;
typedef struct {
CRC_State state;
osMutexId_t mtx;
} HAL_CRC_Control;
static volatile HAL_CRC_Control hal_crc_control = {
.state = CRC_State_Reset,
.mtx = NULL,
};
void furi_hal_crc_init(bool synchronize) {
/* initialize peripheral with default generating polynomial */
LL_CRC_SetInputDataReverseMode(CRC, LL_CRC_INDATA_REVERSE_BYTE);
LL_CRC_SetOutputDataReverseMode(CRC, LL_CRC_OUTDATA_REVERSE_BIT);
LL_CRC_SetPolynomialCoef(CRC, LL_CRC_DEFAULT_CRC32_POLY);
LL_CRC_SetPolynomialSize(CRC, LL_CRC_POLYLENGTH_32B);
LL_CRC_SetInitialData(CRC, LL_CRC_DEFAULT_CRC_INITVALUE);
if(synchronize) {
hal_crc_control.mtx = osMutexNew(NULL);
}
hal_crc_control.state = CRC_State_Ready;
}
void furi_hal_crc_reset() {
furi_check(hal_crc_control.state == CRC_State_Ready);
if(hal_crc_control.mtx) {
osMutexRelease(hal_crc_control.mtx);
}
LL_CRC_ResetCRCCalculationUnit(CRC);
}
static uint32_t furi_hal_crc_handle_8(uint8_t pBuffer[], uint32_t BufferLength) {
uint32_t i; /* input data buffer index */
hal_crc_control.state = CRC_State_Busy;
/* Processing time optimization: 4 bytes are entered in a row with a single word write,
* last bytes must be carefully fed to the CRC calculator to ensure a correct type
* handling by the peripheral */
for(i = 0U; i < (BufferLength / 4U); i++) {
LL_CRC_FeedData32(
CRC,
((uint32_t)pBuffer[4U * i] << 24U) | ((uint32_t)pBuffer[(4U * i) + 1U] << 16U) |
((uint32_t)pBuffer[(4U * i) + 2U] << 8U) | (uint32_t)pBuffer[(4U * i) + 3U]);
}
/* last bytes specific handling */
if((BufferLength % 4U) != 0U) {
if((BufferLength % 4U) == 1U) {
LL_CRC_FeedData8(CRC, pBuffer[4U * i]);
} else if((BufferLength % 4U) == 2U) {
LL_CRC_FeedData16(
CRC, ((uint16_t)(pBuffer[4U * i]) << 8U) | (uint16_t)pBuffer[(4U * i) + 1U]);
} else if((BufferLength % 4U) == 3U) {
LL_CRC_FeedData16(
CRC, ((uint16_t)(pBuffer[4U * i]) << 8U) | (uint16_t)pBuffer[(4U * i) + 1U]);
LL_CRC_FeedData8(CRC, pBuffer[(4U * i) + 2U]);
}
}
hal_crc_control.state = CRC_State_Ready;
/* Return the CRC computed value */
return LL_CRC_ReadData32(CRC);
}
static uint32_t furi_hal_crc_accumulate(uint32_t pBuffer[], uint32_t BufferLength) {
furi_check(hal_crc_control.state == CRC_State_Ready);
if(hal_crc_control.mtx) {
furi_check(osMutexGetOwner(hal_crc_control.mtx) != NULL);
}
return furi_hal_crc_handle_8((uint8_t*)pBuffer, BufferLength);
}
uint32_t furi_hal_crc_feed(void* data, uint16_t length) {
return ~furi_hal_crc_accumulate(data, length);
}
bool furi_hal_crc_acquire(uint32_t timeout) {
furi_assert(hal_crc_control.mtx);
return osMutexAcquire(hal_crc_control.mtx, timeout) == osOK;
}

View File

@@ -0,0 +1,35 @@
#pragma once
#include <stdint.h>
#include <stdbool.h>
#ifdef __cplusplus
extern "C" {
#endif
/** Configure for CRC32 calculation
* @param synchronize enforce acquisition & release in multithreaded environment
*/
void furi_hal_crc_init(bool synchronize);
/** Blocking call to get control of CRC block. Mandatory while RTOS is running
* @param timeout time to wait for CRC to be available. Can be osWaitForever
* @return bool acquisition success
*/
bool furi_hal_crc_acquire(uint32_t timeout);
/** Reset current calculation state and release CRC block
*/
void furi_hal_crc_reset();
/** Process data block. Does not reset current state,
* allowing to process arbitrary data lengths
* @param data pointer to data
* @param length data length
* @return uint32_t CRC32 value
*/
uint32_t furi_hal_crc_feed(void* data, uint16_t length);
#ifdef __cplusplus
}
#endif

View File

@@ -2,17 +2,20 @@
#include <furi.h>
#include <cmsis_os2.h>
#include <stm32wbxx_ll_utils.h>
#define TAG "FuriHalDelay"
uint32_t instructions_per_us;
static volatile uint32_t tick_cnt = 0;
void furi_hal_delay_init(void) {
void furi_hal_delay_init() {
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk;
DWT->CYCCNT = 0U;
instructions_per_us = SystemCoreClock / 1000000.0f;
FURI_LOG_I(TAG, "Init OK");
}
uint32_t furi_hal_delay_instructions_per_microsecond() {
return SystemCoreClock / 1000000;
}
void furi_hal_tick(void) {
@@ -25,7 +28,7 @@ uint32_t furi_hal_get_tick(void) {
void furi_hal_delay_us(float microseconds) {
uint32_t start = DWT->CYCCNT;
uint32_t time_ticks = microseconds * instructions_per_us;
uint32_t time_ticks = microseconds * furi_hal_delay_instructions_per_microsecond();
while((DWT->CYCCNT - start) < time_ticks) {
};
}
@@ -33,8 +36,12 @@ void furi_hal_delay_us(float microseconds) {
// cannot be used in ISR
// TODO add delay_ISR variant
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);
if(!FURI_IS_ISR() && osKernelGetState() == osKernelRunning) {
uint32_t ticks = milliseconds / (1000.0f / osKernelGetTickFreq());
osStatus_t result = osDelay(ticks);
(void)result;
furi_assert(result == osOK);
} else {
furi_hal_delay_us(milliseconds * 1000);
}
}

View File

@@ -14,7 +14,9 @@
#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_TOTAL_PAGES 256
#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)
@@ -72,6 +74,12 @@ size_t furi_hal_flash_get_free_page_count() {
return (end - page_start) / FURI_HAL_FLASH_PAGE_SIZE;
}
void furi_hal_flash_init() {
// Errata 2.2.9, Flash OPTVERR flag is always set after system reset
WRITE_REG(FLASH->SR, FLASH_SR_OPTVERR);
//__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPTVERR);
}
static void furi_hal_flash_unlock() {
/* verify Flash is locked */
furi_check(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != 0U);
@@ -283,6 +291,22 @@ bool furi_hal_flash_erase(uint8_t page) {
return true;
}
static inline bool furi_hal_flash_write_dword_internal(size_t address, uint64_t* data) {
/* Program first word */
*(uint32_t*)address = (uint32_t)*data;
// Barrier to ensure programming is performed in 2 steps, in right order
// (independently of compiler optimization behavior)
__ISB();
/* Program second word */
*(uint32_t*)(address + 4U) = (uint32_t)(*data >> 32U);
/* Wait for last operation to be completed */
furi_check(furi_hal_flash_wait_last_operation(FURI_HAL_FLASH_TIMEOUT));
return true;
}
bool furi_hal_flash_write_dword(size_t address, uint64_t data) {
furi_hal_flash_begin(false);
@@ -296,23 +320,70 @@ bool furi_hal_flash_write_dword(size_t address, uint64_t data) {
/* Set PG bit */
SET_BIT(FLASH->CR, FLASH_CR_PG);
/* Program first word */
*(uint32_t*)address = (uint32_t)data;
// Barrier to ensure programming is performed in 2 steps, in right order
// (independently of compiler optimization behavior)
__ISB();
/* Program second word */
*(uint32_t*)(address + 4U) = (uint32_t)(data >> 32U);
/* Wait for last operation to be completed */
furi_check(furi_hal_flash_wait_last_operation(FURI_HAL_FLASH_TIMEOUT));
/* Do the thing */
furi_check(furi_hal_flash_write_dword_internal(address, &data));
/* If the program operation is completed, disable the PG or FSTPG Bit */
CLEAR_BIT(FLASH->CR, FLASH_CR_PG);
furi_hal_flash_end(false);
/* Wait for last operation to be completed */
furi_check(furi_hal_flash_wait_last_operation(FURI_HAL_FLASH_TIMEOUT));
return true;
}
static size_t furi_hal_flash_get_page_address(uint8_t page) {
return furi_hal_flash_get_base() + page * FURI_HAL_FLASH_PAGE_SIZE;
}
bool furi_hal_flash_program_page(const uint8_t page, const uint8_t* data, uint16_t _length) {
uint16_t length = _length;
furi_check(length <= FURI_HAL_FLASH_PAGE_SIZE);
furi_hal_flash_erase(page);
furi_hal_flash_begin(false);
// Ensure that controller state is valid
furi_check(FLASH->SR == 0);
size_t page_start_address = furi_hal_flash_get_page_address(page);
/* Set PG bit */
SET_BIT(FLASH->CR, FLASH_CR_PG);
size_t i_dwords = 0;
for(i_dwords = 0; i_dwords < (length / 8); ++i_dwords) {
/* Do the thing */
size_t data_offset = i_dwords * 8;
furi_check(furi_hal_flash_write_dword_internal(
page_start_address + data_offset, (uint64_t*)&data[data_offset]));
}
if((length % 8) != 0) {
/* there are more bytes, not fitting into dwords */
uint64_t tail_data = 0;
size_t data_offset = i_dwords * 8;
for(int32_t tail_i = 0; tail_i < (length % 8); ++tail_i) {
tail_data |= (((uint64_t)data[data_offset + tail_i]) << (tail_i * 8));
}
furi_check(
furi_hal_flash_write_dword_internal(page_start_address + data_offset, &tail_data));
}
/* If the program operation is completed, disable the PG or FSTPG Bit */
CLEAR_BIT(FLASH->CR, FLASH_CR_PG);
furi_hal_flash_end(false);
return true;
}
int16_t furi_hal_flash_get_page_number(size_t address) {
const size_t flash_base = furi_hal_flash_get_base();
if((address < flash_base) ||
(address > flash_base + FURI_HAL_FLASH_TOTAL_PAGES * FURI_HAL_FLASH_PAGE_SIZE)) {
return -1;
}
return (address - flash_base) / FURI_HAL_FLASH_PAGE_SIZE;
}

View File

@@ -4,6 +4,10 @@
#include <stdint.h>
#include <stddef.h>
/** Init flash, applying necessary workarounds
*/
void furi_hal_flash_init();
/** Get flash base address
*
* @return pointer to flash base
@@ -78,3 +82,22 @@ bool furi_hal_flash_erase(uint8_t page);
* @return true on success
*/
bool furi_hal_flash_write_dword(size_t address, uint64_t data);
/** Write aligned page data (up to page size)
*
* @warning locking operation with critical section, stales execution
*
* @param address destination address, must be page aligned.
* @param data data to write
* @param length data length
*
* @return true on success
*/
bool furi_hal_flash_program_page(const uint8_t page, const uint8_t* data, uint16_t length);
/** Get flash page number for address
*
* @return page number, -1 for invalid address
*/
int16_t furi_hal_flash_get_page_number(size_t address);

View File

@@ -9,8 +9,15 @@
#define TAG "FuriHalI2C"
void furi_hal_i2c_init() {
void furi_hal_i2c_init_early() {
furi_hal_i2c_bus_power.callback(&furi_hal_i2c_bus_power, FuriHalI2cBusEventInit);
}
void furi_hal_i2c_deinit_early() {
furi_hal_i2c_bus_power.callback(&furi_hal_i2c_bus_power, FuriHalI2cBusEventDeinit);
}
void furi_hal_i2c_init() {
furi_hal_i2c_bus_external.callback(&furi_hal_i2c_bus_external, FuriHalI2cBusEventInit);
FURI_LOG_I(TAG, "Init OK");
}

View File

@@ -27,7 +27,11 @@ static void furi_hal_i2c_bus_power_event(FuriHalI2cBus* bus, FuriHalI2cBusEvent
FURI_CRITICAL_EXIT();
bus->current_handle = NULL;
} else if(event == FuriHalI2cBusEventDeinit) {
osMutexDelete(furi_hal_i2c_bus_power_mutex);
furi_check(osMutexDelete(furi_hal_i2c_bus_power_mutex) == osOK);
FURI_CRITICAL_ENTER();
LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_I2C1);
LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_I2C1);
FURI_CRITICAL_EXIT();
} else if(event == FuriHalI2cBusEventLock) {
furi_check(osMutexAcquire(furi_hal_i2c_bus_power_mutex, osWaitForever) == osOK);
} else if(event == FuriHalI2cBusEventUnlock) {
@@ -51,7 +55,24 @@ FuriHalI2cBus furi_hal_i2c_bus_power = {
osMutexId_t furi_hal_i2c_bus_external_mutex = NULL;
static void furi_hal_i2c_bus_external_event(FuriHalI2cBus* bus, FuriHalI2cBusEvent event) {
if(event == FuriHalI2cBusEventActivate) {
if(event == FuriHalI2cBusEventInit) {
furi_hal_i2c_bus_external_mutex = osMutexNew(NULL);
FURI_CRITICAL_ENTER();
LL_RCC_SetI2CClockSource(LL_RCC_I2C3_CLKSOURCE_PCLK1);
LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_I2C3);
FURI_CRITICAL_EXIT();
bus->current_handle = NULL;
} else if(event == FuriHalI2cBusEventDeinit) {
furi_check(osMutexDelete(furi_hal_i2c_bus_external_mutex) == osOK);
FURI_CRITICAL_ENTER();
LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_I2C3);
LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_I2C3);
FURI_CRITICAL_EXIT();
} else if(event == FuriHalI2cBusEventLock) {
furi_check(osMutexAcquire(furi_hal_i2c_bus_external_mutex, osWaitForever) == osOK);
} else if(event == FuriHalI2cBusEventUnlock) {
furi_check(osMutexRelease(furi_hal_i2c_bus_external_mutex) == osOK);
} else if(event == FuriHalI2cBusEventActivate) {
FURI_CRITICAL_ENTER();
LL_RCC_SetI2CClockSource(LL_RCC_I2C3_CLKSOURCE_PCLK1);
LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_I2C3);

View File

@@ -50,22 +50,14 @@ void furi_hal_info_get(FuriHalInfoValueCallback out, void* context) {
out("hardware_name", name, false, context);
}
// Bootloader Version
const Version* bootloader_version = furi_hal_version_get_bootloader_version();
if(bootloader_version) {
out("bootloader_commit", version_get_githash(bootloader_version), false, context);
out("bootloader_branch", version_get_gitbranch(bootloader_version), false, context);
out("bootloader_branch_num", version_get_gitbranchnum(bootloader_version), false, context);
out("bootloader_version", version_get_version(bootloader_version), false, context);
out("bootloader_build_date", version_get_builddate(bootloader_version), false, context);
string_printf(value, "%d", version_get_target(bootloader_version));
out("bootloader_target", string_get_cstr(value), false, context);
}
// Firmware version
const Version* firmware_version = furi_hal_version_get_firmware_version();
if(firmware_version) {
out("firmware_commit", version_get_githash(firmware_version), false, context);
out("firmware_commit_dirty",
version_get_dirty_flag(firmware_version) ? "true" : "false",
false,
context);
out("firmware_branch", version_get_gitbranch(firmware_version), false, context);
out("firmware_branch_num", version_get_gitbranchnum(firmware_version), false, context);
out("firmware_version", version_get_version(firmware_version), false, context);
@@ -139,4 +131,4 @@ void furi_hal_info_get(FuriHalInfoValueCallback out, void* context) {
out("protobuf_version_minor", string_get_cstr(value), true, context);
string_clear(value);
}
}

View File

@@ -253,7 +253,9 @@ void SysTick_Handler(void) {
}
void USB_LP_IRQHandler(void) {
#ifndef FURI_RAM_EXEC
usbd_poll(&udev);
#endif
}
void IPCC_C1_TX_IRQHandler(void) {
@@ -262,4 +264,4 @@ void IPCC_C1_TX_IRQHandler(void) {
void IPCC_C1_RX_IRQHandler(void) {
HW_IPCC_Rx_Handler();
}
}

View File

@@ -1,4 +1,5 @@
#include <furi_hal_light.h>
#include <furi_hal_delay.h>
#include <lp5562.h>
#define LED_CURRENT_RED 50
@@ -50,3 +51,30 @@ void furi_hal_light_set(Light light, uint8_t value) {
}
furi_hal_i2c_release(&furi_hal_i2c_handle_power);
}
void furi_hal_light_sequence(const char* sequence) {
do {
if(*sequence == 'R') {
furi_hal_light_set(LightRed, 0xFF);
} else if(*sequence == 'r') {
furi_hal_light_set(LightRed, 0x00);
} else if(*sequence == 'G') {
furi_hal_light_set(LightGreen, 0xFF);
} else if(*sequence == 'g') {
furi_hal_light_set(LightGreen, 0x00);
} else if(*sequence == 'B') {
furi_hal_light_set(LightBlue, 0xFF);
} else if(*sequence == 'b') {
furi_hal_light_set(LightBlue, 0x00);
} else if(*sequence == 'W') {
furi_hal_light_set(LightBacklight, 0xFF);
} else if(*sequence == 'w') {
furi_hal_light_set(LightBacklight, 0x00);
} else if(*sequence == '.') {
furi_hal_delay_ms(250);
} else if(*sequence == '-') {
furi_hal_delay_ms(500);
}
sequence++;
} while(*sequence != 0);
}

View File

@@ -56,6 +56,9 @@ const GpioPin gpio_speaker = {.port = GPIOB, .pin = LL_GPIO_PIN_8};
const GpioPin periph_power = {.port = PERIPH_POWER_GPIO_Port, .pin = PERIPH_POWER_Pin};
const GpioPin gpio_usb_dm = {.port = GPIOA, .pin = LL_GPIO_PIN_11};
const GpioPin gpio_usb_dp = {.port = GPIOA, .pin = LL_GPIO_PIN_12};
const InputPin input_pins[] = {
{.gpio = &gpio_button_up, .key = InputKeyUp, .inverted = true, .name = "Up"},
{.gpio = &gpio_button_down, .key = InputKeyDown, .inverted = true, .name = "Down"},
@@ -67,7 +70,22 @@ const InputPin input_pins[] = {
const size_t input_pins_count = sizeof(input_pins) / sizeof(InputPin);
void furi_hal_resources_init(void) {
void furi_hal_resources_init_early() {
furi_hal_gpio_init(&gpio_button_left, GpioModeInput, GpioPullUp, GpioSpeedLow);
furi_hal_gpio_init_simple(&gpio_display_rst, GpioModeOutputPushPull);
furi_hal_gpio_init_simple(&gpio_display_di, GpioModeOutputPushPull);
// Hard reset USB
furi_hal_gpio_init_simple(&gpio_usb_dm, GpioModeOutputOpenDrain);
furi_hal_gpio_init_simple(&gpio_usb_dp, GpioModeOutputOpenDrain);
furi_hal_gpio_write(&gpio_usb_dm, 0);
furi_hal_gpio_write(&gpio_usb_dp, 0);
}
void furi_hal_resources_deinit_early() {
}
void furi_hal_resources_init() {
// Button pins
for(size_t i = 0; i < input_pins_count; i++) {
furi_hal_gpio_init(

View File

@@ -54,6 +54,13 @@ extern const GpioPin gpio_sdcard_cs;
extern const GpioPin gpio_sdcard_cd;
extern const GpioPin gpio_nfc_cs;
extern const GpioPin gpio_button_up;
extern const GpioPin gpio_button_down;
extern const GpioPin gpio_button_right;
extern const GpioPin gpio_button_left;
extern const GpioPin gpio_button_ok;
extern const GpioPin gpio_button_back;
extern const GpioPin gpio_spi_d_miso;
extern const GpioPin gpio_spi_d_mosi;
extern const GpioPin gpio_spi_d_sck;
@@ -87,6 +94,9 @@ extern const GpioPin gpio_speaker;
extern const GpioPin periph_power;
extern const GpioPin gpio_usb_dm;
extern const GpioPin gpio_usb_dp;
#define BUTTON_BACK_GPIO_Port GPIOC
#define BUTTON_BACK_Pin LL_GPIO_PIN_13
#define BUTTON_DOWN_GPIO_Port GPIOC
@@ -193,7 +203,11 @@ extern const GpioPin periph_power;
#define NFC_IRQ_Pin RFID_PULL_Pin
#define NFC_IRQ_GPIO_Port RFID_PULL_GPIO_Port
void furi_hal_resources_init(void);
void furi_hal_resources_init_early();
void furi_hal_resources_deinit_early();
void furi_hal_resources_init();
#ifdef __cplusplus
}

View File

@@ -1,20 +1,84 @@
#include <furi_hal_rtc.h>
#include <furi_hal_light.h>
#include <stm32wbxx_ll_bus.h>
#include <stm32wbxx_ll_pwr.h>
#include <stm32wbxx_ll_rcc.h>
#include <stm32wbxx_ll_rtc.h>
#include <stm32wbxx_ll_utils.h>
#include <furi.h>
#define TAG "FuriHalRtc"
#define RTC_CLOCK_IS_READY() (LL_RCC_LSE_IsReady() && LL_RCC_LSI1_IsReady())
#define FURI_HAL_RTC_HEADER_MAGIC 0x10F1
#define FURI_HAL_RTC_HEADER_VERSION 0
typedef struct {
uint16_t magic;
uint8_t version;
uint8_t unused;
} FuriHalRtcHeader;
typedef struct {
uint8_t log_level : 4;
uint8_t log_reserved : 4;
uint8_t flags;
uint16_t reserved;
uint8_t boot_mode : 4;
uint16_t reserved : 12;
} DeveloperReg;
_Static_assert(sizeof(DeveloperReg) == 4, "DeveloperReg size mismatch");
void furi_hal_rtc_init_early() {
// LSE and RTC
LL_PWR_EnableBkUpAccess();
if(!RTC_CLOCK_IS_READY()) {
// Start LSI1 needed for CSS
LL_RCC_LSI1_Enable();
// Try to start LSE normal way
LL_RCC_LSE_SetDriveCapability(LL_RCC_LSEDRIVE_HIGH);
LL_RCC_LSE_Enable();
uint32_t c = 0;
while(!RTC_CLOCK_IS_READY() && c < 200) {
LL_mDelay(10);
c++;
}
// Plan B: reset backup domain
if(!RTC_CLOCK_IS_READY()) {
furi_hal_light_sequence("rgb R.r.R.r.R");
LL_RCC_ForceBackupDomainReset();
LL_RCC_ReleaseBackupDomainReset();
NVIC_SystemReset();
}
// Set RTC domain clock to LSE
LL_RCC_SetRTCClockSource(LL_RCC_RTC_CLKSOURCE_LSE);
// Enable LSE CSS
LL_RCC_LSE_EnableCSS();
}
// Enable clocking
LL_RCC_EnableRTC();
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_RTCAPB);
// Verify header register
uint32_t data_reg = furi_hal_rtc_get_register(FuriHalRtcRegisterHeader);
FuriHalRtcHeader* data = (FuriHalRtcHeader*)&data_reg;
if(data->magic != FURI_HAL_RTC_HEADER_MAGIC || data->version != FURI_HAL_RTC_HEADER_VERSION) {
// Reset all our registers to ensure consistency
for(size_t i = 0; i < FuriHalRtcRegisterMAX; i++) {
furi_hal_rtc_set_register(i, 0);
}
data->magic = FURI_HAL_RTC_HEADER_MAGIC;
data->version = FURI_HAL_RTC_HEADER_VERSION;
furi_hal_rtc_set_register(FuriHalRtcRegisterHeader, data_reg);
}
}
void furi_hal_rtc_deinit_early() {
}
void furi_hal_rtc_init() {
if(LL_RCC_GetRTCClockSource() != LL_RCC_RTC_CLKSOURCE_LSE) {
LL_RCC_ForceBackupDomainReset();
@@ -77,6 +141,19 @@ bool furi_hal_rtc_is_flag_set(FuriHalRtcFlag flag) {
return data->flags & flag;
}
void furi_hal_rtc_set_boot_mode(FuriHalRtcBootMode mode) {
uint32_t data_reg = furi_hal_rtc_get_register(FuriHalRtcRegisterSystem);
DeveloperReg* data = (DeveloperReg*)&data_reg;
data->boot_mode = mode;
furi_hal_rtc_set_register(FuriHalRtcRegisterSystem, data_reg);
}
FuriHalRtcBootMode furi_hal_rtc_get_boot_mode() {
uint32_t data_reg = furi_hal_rtc_get_register(FuriHalRtcRegisterSystem);
DeveloperReg* data = (DeveloperReg*)&data_reg;
return (FuriHalRtcBootMode)data->boot_mode;
}
void furi_hal_rtc_set_datetime(FuriHalRtcDateTime* datetime) {
furi_assert(datetime);

View File

@@ -11,13 +11,21 @@
#define TAG "FuriHalSpi"
void furi_hal_spi_init_early() {
furi_hal_spi_bus_init(&furi_hal_spi_bus_d);
furi_hal_spi_bus_handle_init(&furi_hal_spi_bus_handle_display);
}
void furi_hal_spi_deinit_early() {
furi_hal_spi_bus_handle_deinit(&furi_hal_spi_bus_handle_display);
furi_hal_spi_bus_deinit(&furi_hal_spi_bus_d);
}
void furi_hal_spi_init() {
furi_hal_spi_bus_init(&furi_hal_spi_bus_r);
furi_hal_spi_bus_init(&furi_hal_spi_bus_d);
furi_hal_spi_bus_handle_init(&furi_hal_spi_bus_handle_subghz);
furi_hal_spi_bus_handle_init(&furi_hal_spi_bus_handle_nfc);
furi_hal_spi_bus_handle_init(&furi_hal_spi_bus_handle_display);
furi_hal_spi_bus_handle_init(&furi_hal_spi_bus_handle_sd_fast);
furi_hal_spi_bus_handle_init(&furi_hal_spi_bus_handle_sd_slow);

View File

@@ -80,7 +80,11 @@ static void furi_hal_spi_bus_r_event_callback(FuriHalSpiBus* bus, FuriHalSpiBusE
FURI_CRITICAL_EXIT();
bus->current_handle = NULL;
} else if(event == FuriHalSpiBusEventDeinit) {
furi_check(osMutexDelete(furi_hal_spi_bus_r_mutex));
furi_check(osMutexDelete(furi_hal_spi_bus_r_mutex) == osOK);
FURI_CRITICAL_ENTER();
LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_SPI1);
LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_SPI1);
FURI_CRITICAL_EXIT();
} else if(event == FuriHalSpiBusEventLock) {
furi_check(osMutexAcquire(furi_hal_spi_bus_r_mutex, osWaitForever) == osOK);
} else if(event == FuriHalSpiBusEventUnlock) {
@@ -111,7 +115,11 @@ static void furi_hal_spi_bus_d_event_callback(FuriHalSpiBus* bus, FuriHalSpiBusE
FURI_CRITICAL_EXIT();
bus->current_handle = NULL;
} else if(event == FuriHalSpiBusEventDeinit) {
furi_check(osMutexDelete(furi_hal_spi_bus_d_mutex));
furi_check(osMutexDelete(furi_hal_spi_bus_d_mutex) == osOK);
FURI_CRITICAL_ENTER();
LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_SPI2);
LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_SPI2);
FURI_CRITICAL_EXIT();
} else if(event == FuriHalSpiBusEventLock) {
furi_check(osMutexAcquire(furi_hal_spi_bus_d_mutex, osWaitForever) == osOK);
} else if(event == FuriHalSpiBusEventUnlock) {

View File

@@ -64,6 +64,11 @@ void furi_hal_vcp_init() {
vcp->tx_stream = xStreamBufferCreate(VCP_TX_BUF_SIZE, 1);
vcp->rx_stream = xStreamBufferCreate(VCP_RX_BUF_SIZE, 1);
if(furi_hal_rtc_get_boot_mode() != FuriHalRtcBootModeNormal) {
FURI_LOG_W(TAG, "Skipped worker init: device in special startup mode=");
return;
}
vcp->thread = furi_thread_alloc();
furi_thread_set_name(vcp->thread, "VcpDriver");
furi_thread_set_stack_size(vcp->thread, 1024);

View File

@@ -192,7 +192,7 @@ void furi_hal_version_init() {
furi_crash(NULL);
}
furi_hal_rtc_set_register(FuriHalRtcRegisterSystemVersion, (uint32_t)version_get());
furi_hal_rtc_set_register(FuriHalRtcRegisterVersion, (uint32_t)version_get());
FURI_LOG_I(TAG, "Init OK");
}
@@ -280,15 +280,6 @@ const struct Version* furi_hal_version_get_firmware_version(void) {
return version_get();
}
const struct Version* furi_hal_version_get_bootloader_version(void) {
#ifdef NO_BOOTLOADER
return 0;
#else
/* Backup register which points to structure in flash memory */
return (const struct Version*)furi_hal_rtc_get_register(FuriHalRtcRegisterBootVersion);
#endif
}
size_t furi_hal_version_uid_size() {
return 64 / 8;
}