[FL-1666] Bootloader: info screen when we going to DFU. FuriHal: port SPI to LL. Cleanup. (#634)
* FuriHal: port spi to ll. Bootloader: add spi and display. * Makefile: rollback disabled freertos introspection * FuriHal: spi lock asserts. F6: minor cleanup port sdcard shenanigans to furi_hal_gpio. * SdCard: port missing bits to furi-hal-gpio * FuriHal: fix broken RX in SPI, update SPI API usage. RFAL: more asserts in SPI platform code. * GUI: clear canvas on start. FuriHal: no pullup on radio spi bus. * FuriHal: use check instead of assert in spi lock routines * FuriHal: remove timeouts * SdHal: add guard time to SDCARD CS PIN control. * FuriHal: proper name for SPI device reconfigure routine. SdHal: one more enterprise delay and better documentation. * Bootloader: update DFU text and add image. * FuriHal: drop unused ST HAL modules. * SdHal: fixed swapped hal_gpio_init_ex arguments * SpiHal: fixed swapped hal_gpio_init_ex arguments * IrdaHal: use hal_gpio_init instead of hal_gpio_init_ex * RfidHal: fixed swapped hal_gpio_init_ex arguments Co-authored-by: DrZlo13 <who.just.the.doctor@gmail.com>
This commit is contained in:
		
							parent
							
								
									5ed9bdbc37
								
							
						
					
					
						commit
						37d7870e52
					
				| @ -21,6 +21,7 @@ Canvas* canvas_init() { | |||||||
|     u8g2_InitDisplay(&canvas->fb); |     u8g2_InitDisplay(&canvas->fb); | ||||||
|     u8g2_SetContrast(&canvas->fb, 36); |     u8g2_SetContrast(&canvas->fb, 36); | ||||||
|     // wake up display
 |     // wake up display
 | ||||||
|  |     u8g2_ClearBuffer(&canvas->fb); | ||||||
|     u8g2_SetPowerSave(&canvas->fb, 0); |     u8g2_SetPowerSave(&canvas->fb, 0); | ||||||
|     u8g2_SendBuffer(&canvas->fb); |     u8g2_SendBuffer(&canvas->fb); | ||||||
| 
 | 
 | ||||||
|  | |||||||
| @ -89,6 +89,9 @@ const uint8_t *_I_ButtonLeft_4x7[] = {_I_ButtonLeft_4x7_0}; | |||||||
| const uint8_t _I_ButtonLeftSmall_3x5_0[] = {0x04,0x06,0x07,0x06,0x04,}; | const uint8_t _I_ButtonLeftSmall_3x5_0[] = {0x04,0x06,0x07,0x06,0x04,}; | ||||||
| const uint8_t *_I_ButtonLeftSmall_3x5[] = {_I_ButtonLeftSmall_3x5_0}; | const uint8_t *_I_ButtonLeftSmall_3x5[] = {_I_ButtonLeftSmall_3x5_0}; | ||||||
| 
 | 
 | ||||||
|  | const uint8_t _I_Warning_30x23_0[] = {0x00,0xC0,0x00,0x00,0x00,0xE0,0x01,0x00,0x00,0xF0,0x03,0x00,0x00,0xF0,0x03,0x00,0x00,0xF8,0x07,0x00,0x00,0x3C,0x0F,0x00,0x00,0x3C,0x0F,0x00,0x00,0x3E,0x1F,0x00,0x00,0x3F,0x3F,0x00,0x00,0x3F,0x3F,0x00,0x80,0x3F,0x7F,0x00,0xC0,0x3F,0xFF,0x00,0xC0,0x3F,0xFF,0x00,0xE0,0x3F,0xFF,0x01,0xF0,0x3F,0xFF,0x03,0xF0,0x3F,0xFF,0x03,0xF8,0x3F,0xFF,0x07,0xFC,0xFF,0xFF,0x0F,0xFC,0xFF,0xFF,0x0F,0xFE,0x3F,0xFF,0x1F,0xFF,0x3F,0xFF,0x3F,0xFF,0xFF,0xFF,0x3F,0xFE,0xFF,0xFF,0x1F,}; | ||||||
|  | const uint8_t *_I_Warning_30x23[] = {_I_Warning_30x23_0}; | ||||||
|  | 
 | ||||||
| const uint8_t _I_ButtonRight_4x7_0[] = {0x01,0x03,0x07,0x0F,0x07,0x03,0x01,}; | const uint8_t _I_ButtonRight_4x7_0[] = {0x01,0x03,0x07,0x0F,0x07,0x03,0x01,}; | ||||||
| const uint8_t *_I_ButtonRight_4x7[] = {_I_ButtonRight_4x7_0}; | const uint8_t *_I_ButtonRight_4x7[] = {_I_ButtonRight_4x7_0}; | ||||||
| 
 | 
 | ||||||
| @ -842,6 +845,7 @@ const Icon I_125_10px = {.width=10,.height=10,.frame_count=1,.frame_rate=0,.fram | |||||||
| const Icon I_ButtonRightSmall_3x5 = {.width=3,.height=5,.frame_count=1,.frame_rate=0,.frames=_I_ButtonRightSmall_3x5}; | const Icon I_ButtonRightSmall_3x5 = {.width=3,.height=5,.frame_count=1,.frame_rate=0,.frames=_I_ButtonRightSmall_3x5}; | ||||||
| const Icon I_ButtonLeft_4x7 = {.width=4,.height=7,.frame_count=1,.frame_rate=0,.frames=_I_ButtonLeft_4x7}; | const Icon I_ButtonLeft_4x7 = {.width=4,.height=7,.frame_count=1,.frame_rate=0,.frames=_I_ButtonLeft_4x7}; | ||||||
| const Icon I_ButtonLeftSmall_3x5 = {.width=3,.height=5,.frame_count=1,.frame_rate=0,.frames=_I_ButtonLeftSmall_3x5}; | const Icon I_ButtonLeftSmall_3x5 = {.width=3,.height=5,.frame_count=1,.frame_rate=0,.frames=_I_ButtonLeftSmall_3x5}; | ||||||
|  | const Icon I_Warning_30x23 = {.width=30,.height=23,.frame_count=1,.frame_rate=0,.frames=_I_Warning_30x23}; | ||||||
| const Icon I_ButtonRight_4x7 = {.width=4,.height=7,.frame_count=1,.frame_rate=0,.frames=_I_ButtonRight_4x7}; | const Icon I_ButtonRight_4x7 = {.width=4,.height=7,.frame_count=1,.frame_rate=0,.frames=_I_ButtonRight_4x7}; | ||||||
| const Icon I_ButtonCenter_7x7 = {.width=7,.height=7,.frame_count=1,.frame_rate=0,.frames=_I_ButtonCenter_7x7}; | const Icon I_ButtonCenter_7x7 = {.width=7,.height=7,.frame_count=1,.frame_rate=0,.frames=_I_ButtonCenter_7x7}; | ||||||
| const Icon I_FX_SittingB_40x27 = {.width=40,.height=27,.frame_count=1,.frame_rate=0,.frames=_I_FX_SittingB_40x27}; | const Icon I_FX_SittingB_40x27 = {.width=40,.height=27,.frame_count=1,.frame_rate=0,.frames=_I_FX_SittingB_40x27}; | ||||||
|  | |||||||
| @ -21,6 +21,7 @@ extern const Icon I_125_10px; | |||||||
| extern const Icon I_ButtonRightSmall_3x5; | extern const Icon I_ButtonRightSmall_3x5; | ||||||
| extern const Icon I_ButtonLeft_4x7; | extern const Icon I_ButtonLeft_4x7; | ||||||
| extern const Icon I_ButtonLeftSmall_3x5; | extern const Icon I_ButtonLeftSmall_3x5; | ||||||
|  | extern const Icon I_Warning_30x23; | ||||||
| extern const Icon I_ButtonRight_4x7; | extern const Icon I_ButtonRight_4x7; | ||||||
| extern const Icon I_ButtonCenter_7x7; | extern const Icon I_ButtonCenter_7x7; | ||||||
| extern const Icon I_FX_SittingB_40x27; | extern const Icon I_FX_SittingB_40x27; | ||||||
|  | |||||||
							
								
								
									
										
											BIN
										
									
								
								assets/icons/Common/Warning_30x23.png
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										
											BIN
										
									
								
								assets/icons/Common/Warning_30x23.png
									
									
									
									
									
										Normal file
									
								
							
										
											Binary file not shown.
										
									
								
							| After Width: | Height: | Size: 347 B | 
| @ -12,6 +12,33 @@ TARGET			?= f6 | |||||||
| TARGET_DIR		= targets/$(TARGET) | TARGET_DIR		= targets/$(TARGET) | ||||||
| include			$(TARGET_DIR)/target.mk | include			$(TARGET_DIR)/target.mk | ||||||
| 
 | 
 | ||||||
|  | LIB_DIR			= $(PROJECT_ROOT)/lib | ||||||
|  | 
 | ||||||
|  | # U8G2 display library
 | ||||||
|  | U8G2_DIR		= $(LIB_DIR)/u8g2 | ||||||
|  | CFLAGS			+= -I$(U8G2_DIR) | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8x8_d_st7565.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_d_setup.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_intersection.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_setup.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_d_memory.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8x8_cad.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8x8_byte.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8x8_gpio.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8x8_display.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8x8_setup.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_hvline.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_line.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_ll_hvline.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_circle.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_box.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_buffer.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_font.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_fonts.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8x8_8x8.c | ||||||
|  | C_SOURCES		+= $(U8G2_DIR)/u8g2_bitmap.c | ||||||
|  | 
 | ||||||
|  | 
 | ||||||
| include			$(PROJECT_ROOT)/make/git.mk | include			$(PROJECT_ROOT)/make/git.mk | ||||||
| include			$(PROJECT_ROOT)/make/toolchain.mk | include			$(PROJECT_ROOT)/make/toolchain.mk | ||||||
| include			$(PROJECT_ROOT)/make/rules.mk | include			$(PROJECT_ROOT)/make/rules.mk | ||||||
|  | |||||||
							
								
								
									
										189
									
								
								bootloader/targets/f6/furi-hal/furi-hal-gpio.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										189
									
								
								bootloader/targets/f6/furi-hal/furi-hal-gpio.c
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,189 @@ | |||||||
|  | #include <furi-hal-gpio.h> | ||||||
|  | #include <stddef.h> | ||||||
|  | #include <assert.h> | ||||||
|  | 
 | ||||||
|  | #define GET_SYSCFG_EXTI_PORT(gpio)                \ | ||||||
|  |     (((gpio) == (GPIOA)) ? LL_SYSCFG_EXTI_PORTA : \ | ||||||
|  |      ((gpio) == (GPIOB)) ? LL_SYSCFG_EXTI_PORTB : \ | ||||||
|  |      ((gpio) == (GPIOC)) ? LL_SYSCFG_EXTI_PORTC : \ | ||||||
|  |      ((gpio) == (GPIOD)) ? LL_SYSCFG_EXTI_PORTD : \ | ||||||
|  |      ((gpio) == (GPIOE)) ? LL_SYSCFG_EXTI_PORTE : \ | ||||||
|  |                            LL_SYSCFG_EXTI_PORTH) | ||||||
|  | 
 | ||||||
|  | #define GPIO_PIN_MAP(pin, prefix)               \ | ||||||
|  |     (((pin) == (LL_GPIO_PIN_0))  ? prefix##0 :  \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_1))  ? prefix##1 :  \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_2))  ? prefix##2 :  \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_3))  ? prefix##3 :  \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_4))  ? prefix##4 :  \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_5))  ? prefix##5 :  \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_6))  ? prefix##6 :  \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_7))  ? prefix##7 :  \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_8))  ? prefix##8 :  \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_9))  ? prefix##9 :  \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_10)) ? prefix##10 : \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_11)) ? prefix##11 : \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_12)) ? prefix##12 : \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_13)) ? prefix##13 : \ | ||||||
|  |      ((pin) == (LL_GPIO_PIN_14)) ? prefix##14 : \ | ||||||
|  |                                    prefix##15) | ||||||
|  | 
 | ||||||
|  | #define GET_SYSCFG_EXTI_LINE(pin) GPIO_PIN_MAP(pin, LL_SYSCFG_EXTI_LINE) | ||||||
|  | #define GET_EXTI_LINE(pin) GPIO_PIN_MAP(pin, LL_EXTI_LINE_) | ||||||
|  | 
 | ||||||
|  | static volatile GpioInterrupt gpio_interrupt[GPIO_NUMBER]; | ||||||
|  | 
 | ||||||
|  | static uint8_t 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; | ||||||
|  |     } | ||||||
|  |     return pin_num; | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void hal_gpio_init_simple(const GpioPin* gpio, const GpioMode mode) { | ||||||
|  |     hal_gpio_init(gpio, mode, GpioPullNo, GpioSpeedLow); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void hal_gpio_init( | ||||||
|  |     const GpioPin* gpio, | ||||||
|  |     const GpioMode mode, | ||||||
|  |     const GpioPull pull, | ||||||
|  |     const GpioSpeed speed) { | ||||||
|  |     // we cannot set alternate mode in this function
 | ||||||
|  |     assert(mode != GpioModeAltFunctionPushPull); | ||||||
|  |     assert(mode != GpioModeAltFunctionOpenDrain); | ||||||
|  | 
 | ||||||
|  |     hal_gpio_init_ex(gpio, mode, pull, speed, GpioAltFnUnused); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void hal_gpio_init_ex( | ||||||
|  |     const GpioPin* gpio, | ||||||
|  |     const GpioMode mode, | ||||||
|  |     const GpioPull pull, | ||||||
|  |     const GpioSpeed speed, | ||||||
|  |     const GpioAltFn alt_fn) { | ||||||
|  |     uint32_t sys_exti_port = GET_SYSCFG_EXTI_PORT(gpio->port); | ||||||
|  |     uint32_t sys_exti_line = GET_SYSCFG_EXTI_LINE(gpio->pin); | ||||||
|  |     uint32_t exti_line = GET_EXTI_LINE(gpio->pin); | ||||||
|  | 
 | ||||||
|  |     // Configure gpio with interrupts disabled
 | ||||||
|  |     __disable_irq(); | ||||||
|  |     // Set gpio speed
 | ||||||
|  |     if(speed == GpioSpeedLow) { | ||||||
|  |         LL_GPIO_SetPinSpeed(gpio->port, gpio->pin, LL_GPIO_SPEED_FREQ_LOW); | ||||||
|  |     } else if(speed == GpioSpeedMedium) { | ||||||
|  |         LL_GPIO_SetPinSpeed(gpio->port, gpio->pin, LL_GPIO_SPEED_FREQ_MEDIUM); | ||||||
|  |     } else if(speed == GpioSpeedHigh) { | ||||||
|  |         LL_GPIO_SetPinSpeed(gpio->port, gpio->pin, LL_GPIO_SPEED_FREQ_HIGH); | ||||||
|  |     } else { | ||||||
|  |         LL_GPIO_SetPinSpeed(gpio->port, gpio->pin, LL_GPIO_SPEED_FREQ_VERY_HIGH); | ||||||
|  |     } | ||||||
|  |     // Set gpio pull mode
 | ||||||
|  |     if(pull == GpioPullNo) { | ||||||
|  |         LL_GPIO_SetPinPull(gpio->port, gpio->pin, LL_GPIO_PULL_NO); | ||||||
|  |     } else if(pull == GpioPullUp) { | ||||||
|  |         LL_GPIO_SetPinPull(gpio->port, gpio->pin, LL_GPIO_PULL_UP); | ||||||
|  |     } else { | ||||||
|  |         LL_GPIO_SetPinPull(gpio->port, gpio->pin, LL_GPIO_PULL_DOWN); | ||||||
|  |     } | ||||||
|  |     // Set gpio mode
 | ||||||
|  |     if(mode >= GpioModeInterruptRise) { | ||||||
|  |         // Set pin in interrupt mode
 | ||||||
|  |         LL_GPIO_SetPinMode(gpio->port, gpio->pin, LL_GPIO_MODE_INPUT); | ||||||
|  |         LL_SYSCFG_SetEXTISource(sys_exti_port, sys_exti_line); | ||||||
|  |         if(mode == GpioModeInterruptRise || mode == GpioModeInterruptRiseFall) { | ||||||
|  |             LL_EXTI_EnableIT_0_31(exti_line); | ||||||
|  |             LL_EXTI_EnableRisingTrig_0_31(exti_line); | ||||||
|  |         } | ||||||
|  |         if(mode == GpioModeInterruptFall || mode == GpioModeInterruptRiseFall) { | ||||||
|  |             LL_EXTI_EnableIT_0_31(exti_line); | ||||||
|  |             LL_EXTI_EnableFallingTrig_0_31(exti_line); | ||||||
|  |         } | ||||||
|  |         if(mode == GpioModeEventRise || mode == GpioModeInterruptRiseFall) { | ||||||
|  |             LL_EXTI_EnableEvent_0_31(exti_line); | ||||||
|  |             LL_EXTI_EnableRisingTrig_0_31(exti_line); | ||||||
|  |         } | ||||||
|  |         if(mode == GpioModeEventFall || mode == GpioModeInterruptRiseFall) { | ||||||
|  |             LL_EXTI_EnableEvent_0_31(exti_line); | ||||||
|  |             LL_EXTI_EnableFallingTrig_0_31(exti_line); | ||||||
|  |         } | ||||||
|  |     } else { | ||||||
|  |         // Disable interrupt if it was set
 | ||||||
|  |         if(LL_SYSCFG_GetEXTISource(sys_exti_line) == sys_exti_port && | ||||||
|  |            LL_EXTI_IsEnabledIT_0_31(exti_line)) { | ||||||
|  |             LL_EXTI_DisableIT_0_31(exti_line); | ||||||
|  |             LL_EXTI_DisableRisingTrig_0_31(exti_line); | ||||||
|  |             LL_EXTI_DisableFallingTrig_0_31(exti_line); | ||||||
|  |         } | ||||||
|  |         // Set not interrupt pin modes
 | ||||||
|  |         if(mode == GpioModeInput) { | ||||||
|  |             LL_GPIO_SetPinMode(gpio->port, gpio->pin, LL_GPIO_MODE_INPUT); | ||||||
|  |         } else if(mode == GpioModeOutputPushPull || mode == GpioModeAltFunctionPushPull) { | ||||||
|  |             LL_GPIO_SetPinMode(gpio->port, gpio->pin, LL_GPIO_MODE_OUTPUT); | ||||||
|  |             LL_GPIO_SetPinOutputType(gpio->port, gpio->pin, LL_GPIO_OUTPUT_PUSHPULL); | ||||||
|  |         } else if(mode == GpioModeOutputOpenDrain || mode == GpioModeAltFunctionOpenDrain) { | ||||||
|  |             LL_GPIO_SetPinMode(gpio->port, gpio->pin, LL_GPIO_MODE_OUTPUT); | ||||||
|  |             LL_GPIO_SetPinOutputType(gpio->port, gpio->pin, LL_GPIO_OUTPUT_OPENDRAIN); | ||||||
|  |         } else if(mode == GpioModeAnalog) { | ||||||
|  |             LL_GPIO_SetPinMode(gpio->port, gpio->pin, LL_GPIO_MODE_ANALOG); | ||||||
|  |         } | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     if(mode == GpioModeAltFunctionPushPull || mode == GpioModeAltFunctionOpenDrain) { | ||||||
|  |         // enable alternate mode
 | ||||||
|  |         LL_GPIO_SetPinMode(gpio->port, gpio->pin, LL_GPIO_MODE_ALTERNATE); | ||||||
|  | 
 | ||||||
|  |         // set alternate function
 | ||||||
|  |         if(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); | ||||||
|  |         } | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     __enable_irq(); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void hal_gpio_add_int_callback(const GpioPin* gpio, GpioExtiCallback cb, void* ctx) { | ||||||
|  |     assert(gpio); | ||||||
|  |     assert(cb); | ||||||
|  | 
 | ||||||
|  |     __disable_irq(); | ||||||
|  |     uint8_t pin_num = hal_gpio_get_pin_num(gpio); | ||||||
|  |     gpio_interrupt[pin_num].callback = cb; | ||||||
|  |     gpio_interrupt[pin_num].context = ctx; | ||||||
|  |     gpio_interrupt[pin_num].ready = true; | ||||||
|  |     __enable_irq(); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void hal_gpio_enable_int_callback(const GpioPin* gpio) { | ||||||
|  |     assert(gpio); | ||||||
|  | 
 | ||||||
|  |     __disable_irq(); | ||||||
|  |     uint8_t pin_num = hal_gpio_get_pin_num(gpio); | ||||||
|  |     if(gpio_interrupt[pin_num].callback) { | ||||||
|  |         gpio_interrupt[pin_num].ready = true; | ||||||
|  |     } | ||||||
|  |     __enable_irq(); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void hal_gpio_disable_int_callback(const GpioPin* gpio) { | ||||||
|  |     assert(gpio); | ||||||
|  | 
 | ||||||
|  |     __disable_irq(); | ||||||
|  |     uint8_t pin_num = hal_gpio_get_pin_num(gpio); | ||||||
|  |     gpio_interrupt[pin_num].ready = false; | ||||||
|  |     __enable_irq(); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void hal_gpio_remove_int_callback(const GpioPin* gpio) { | ||||||
|  |     assert(gpio); | ||||||
|  | 
 | ||||||
|  |     __disable_irq(); | ||||||
|  |     uint8_t pin_num = hal_gpio_get_pin_num(gpio); | ||||||
|  |     gpio_interrupt[pin_num].callback = NULL; | ||||||
|  |     gpio_interrupt[pin_num].context = NULL; | ||||||
|  |     gpio_interrupt[pin_num].ready = false; | ||||||
|  |     __enable_irq(); | ||||||
|  | } | ||||||
							
								
								
									
										264
									
								
								bootloader/targets/f6/furi-hal/furi-hal-gpio.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										264
									
								
								bootloader/targets/f6/furi-hal/furi-hal-gpio.h
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,264 @@ | |||||||
|  | #pragma once | ||||||
|  | #include "main.h" | ||||||
|  | #include "stdbool.h" | ||||||
|  | #include <stm32wbxx_ll_gpio.h> | ||||||
|  | #include <stm32wbxx_ll_system.h> | ||||||
|  | #include <stm32wbxx_ll_exti.h> | ||||||
|  | 
 | ||||||
|  | #ifdef __cplusplus | ||||||
|  | extern "C" { | ||||||
|  | #endif | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Number of gpio on one port | ||||||
|  |  */ | ||||||
|  | #define GPIO_NUMBER (16U) | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Interrupt callback prototype | ||||||
|  |  */ | ||||||
|  | typedef void (*GpioExtiCallback)(void* ctx); | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Gpio interrupt type | ||||||
|  |  */ | ||||||
|  | typedef struct { | ||||||
|  |     GpioExtiCallback callback; | ||||||
|  |     void* context; | ||||||
|  |     volatile bool ready; | ||||||
|  | } GpioInterrupt; | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Gpio modes | ||||||
|  |  */ | ||||||
|  | typedef enum { | ||||||
|  |     GpioModeInput, | ||||||
|  |     GpioModeOutputPushPull, | ||||||
|  |     GpioModeOutputOpenDrain, | ||||||
|  |     GpioModeAltFunctionPushPull, | ||||||
|  |     GpioModeAltFunctionOpenDrain, | ||||||
|  |     GpioModeAnalog, | ||||||
|  |     GpioModeInterruptRise, | ||||||
|  |     GpioModeInterruptFall, | ||||||
|  |     GpioModeInterruptRiseFall, | ||||||
|  |     GpioModeEventRise, | ||||||
|  |     GpioModeEventFall, | ||||||
|  |     GpioModeEventRiseFall, | ||||||
|  | } GpioMode; | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Gpio pull modes | ||||||
|  |  */ | ||||||
|  | typedef enum { | ||||||
|  |     GpioPullNo, | ||||||
|  |     GpioPullUp, | ||||||
|  |     GpioPullDown, | ||||||
|  | } GpioPull; | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Gpio speed modes | ||||||
|  |  */ | ||||||
|  | typedef enum { | ||||||
|  |     GpioSpeedLow, | ||||||
|  |     GpioSpeedMedium, | ||||||
|  |     GpioSpeedHigh, | ||||||
|  |     GpioSpeedVeryHigh, | ||||||
|  | } GpioSpeed; | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Gpio alternate functions | ||||||
|  |  */ | ||||||
|  | typedef enum { | ||||||
|  |     GpioAltFn0MCO = 0, /*!< MCO Alternate Function mapping */ | ||||||
|  |     GpioAltFn0LSCO = 0, /*!< LSCO Alternate Function mapping */ | ||||||
|  |     GpioAltFn0JTMS_SWDIO = 0, /*!< JTMS-SWDIO Alternate Function mapping */ | ||||||
|  |     GpioAltFn0JTCK_SWCLK = 0, /*!< JTCK-SWCLK Alternate Function mapping */ | ||||||
|  |     GpioAltFn0JTDI = 0, /*!< JTDI Alternate Function mapping */ | ||||||
|  |     GpioAltFn0RTC_OUT = 0, /*!< RCT_OUT Alternate Function mapping */ | ||||||
|  |     GpioAltFn0JTD_TRACE = 0, /*!< JTDO-TRACESWO Alternate Function mapping */ | ||||||
|  |     GpioAltFn0NJTRST = 0, /*!< NJTRST Alternate Function mapping */ | ||||||
|  |     GpioAltFn0RTC_REFIN = 0, /*!< RTC_REFIN Alternate Function mapping */ | ||||||
|  |     GpioAltFn0TRACED0 = 0, /*!< TRACED0 Alternate Function mapping */ | ||||||
|  |     GpioAltFn0TRACED1 = 0, /*!< TRACED1 Alternate Function mapping */ | ||||||
|  |     GpioAltFn0TRACED2 = 0, /*!< TRACED2 Alternate Function mapping */ | ||||||
|  |     GpioAltFn0TRACED3 = 0, /*!< TRACED3 Alternate Function mapping */ | ||||||
|  |     GpioAltFn0TRIG_INOUT = 0, /*!< TRIG_INOUT Alternate Function mapping */ | ||||||
|  |     GpioAltFn0TRACECK = 0, /*!< TRACECK Alternate Function mapping */ | ||||||
|  |     GpioAltFn0SYS = 0, /*!< System Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn1TIM1 = 1, /*!< TIM1 Alternate Function mapping */ | ||||||
|  |     GpioAltFn1TIM2 = 1, /*!< TIM2 Alternate Function mapping */ | ||||||
|  |     GpioAltFn1LPTIM1 = 1, /*!< LPTIM1 Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn2TIM2 = 2, /*!< TIM2 Alternate Function mapping */ | ||||||
|  |     GpioAltFn2TIM1 = 2, /*!< TIM1 Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn3SAI1 = 3, /*!< SAI1_CK1 Alternate Function mapping */ | ||||||
|  |     GpioAltFn3SPI2 = 3, /*!< SPI2 Alternate Function mapping */ | ||||||
|  |     GpioAltFn3TIM1 = 3, /*!< TIM1 Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn4I2C1 = 4, /*!< I2C1 Alternate Function mapping */ | ||||||
|  |     GpioAltFn4I2C3 = 4, /*!< I2C3 Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn5SPI1 = 5, /*!< SPI1 Alternate Function mapping */ | ||||||
|  |     GpioAltFn5SPI2 = 5, /*!< SPI2 Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn6MCO = 6, /*!< MCO Alternate Function mapping */ | ||||||
|  |     GpioAltFn6LSCO = 6, /*!< LSCO Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB0 = 6, /*!< RF_DTB0 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB1 = 6, /*!< RF_DTB1 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB2 = 6, /*!< RF_DTB2 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB3 = 6, /*!< RF_DTB3 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB4 = 6, /*!< RF_DTB4 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB5 = 6, /*!< RF_DTB5 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB6 = 6, /*!< RF_DTB6 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB7 = 6, /*!< RF_DTB7 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB8 = 6, /*!< RF_DTB8 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB9 = 6, /*!< RF_DTB9 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB10 = 6, /*!< RF_DTB10 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB11 = 6, /*!< RF_DTB11 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB12 = 6, /*!< RF_DTB12 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB13 = 6, /*!< RF_DTB13 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB14 = 6, /*!< RF_DTB14 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB15 = 6, /*!< RF_DTB15 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB16 = 6, /*!< RF_DTB16 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB17 = 6, /*!< RF_DTB17 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_DTB18 = 6, /*!< RF_DTB18 Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_MISO = 6, /*!< RF_MISO Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_MOSI = 6, /*!< RF_MOSI Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_SCK = 6, /*!< RF_SCK Alternate Function mapping */ | ||||||
|  |     GpioAltFn6RF_NSS = 6, /*!< RF_NSS Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn7USART1 = 7, /*!< USART1 Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn8LPUART1 = 8, /*!< LPUART1 Alternate Function mapping */ | ||||||
|  |     GpioAltFn8IR = 8, /*!< IR Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn9TSC = 9, /*!< TSC Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn10QUADSPI = 10, /*!< QUADSPI Alternate Function mapping */ | ||||||
|  |     GpioAltFn10USB = 10, /*!< USB Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn11LCD = 11, /*!< LCD Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn12COMP1 = 12, /*!< COMP1 Alternate Function mapping */ | ||||||
|  |     GpioAltFn12COMP2 = 12, /*!< COMP2 Alternate Function mapping */ | ||||||
|  |     GpioAltFn12TIM1 = 12, /*!< TIM1 Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn13SAI1 = 13, /*!< SAI1 Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn14TIM2 = 14, /*!< TIM2 Alternate Function mapping */ | ||||||
|  |     GpioAltFn14TIM16 = 14, /*!< TIM16 Alternate Function mapping */ | ||||||
|  |     GpioAltFn14TIM17 = 14, /*!< TIM17 Alternate Function mapping */ | ||||||
|  |     GpioAltFn14LPTIM2 = 14, /*!< LPTIM2 Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFn15EVENTOUT = 15, /*!< EVENTOUT Alternate Function mapping */ | ||||||
|  | 
 | ||||||
|  |     GpioAltFnUnused = 16, /*!< just dummy value */ | ||||||
|  | } GpioAltFn; | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Gpio structure | ||||||
|  |  */ | ||||||
|  | typedef struct { | ||||||
|  |     GPIO_TypeDef* port; | ||||||
|  |     uint16_t pin; | ||||||
|  | } GpioPin; | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * GPIO initialization function, simple version | ||||||
|  |  * @param gpio  GpioPin | ||||||
|  |  * @param mode  GpioMode | ||||||
|  |  */ | ||||||
|  | void hal_gpio_init_simple(const GpioPin* gpio, const GpioMode mode); | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * GPIO initialization function, normal version | ||||||
|  |  * @param gpio  GpioPin | ||||||
|  |  * @param mode  GpioMode | ||||||
|  |  * @param pull  GpioPull | ||||||
|  |  * @param speed GpioSpeed | ||||||
|  |  */ | ||||||
|  | void hal_gpio_init( | ||||||
|  |     const GpioPin* gpio, | ||||||
|  |     const GpioMode mode, | ||||||
|  |     const GpioPull pull, | ||||||
|  |     const GpioSpeed speed); | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * GPIO initialization function, extended version | ||||||
|  |  * @param gpio  GpioPin | ||||||
|  |  * @param mode  GpioMode | ||||||
|  |  * @param pull  GpioPull | ||||||
|  |  * @param speed GpioSpeed | ||||||
|  |  * @param alt_fn GpioAltFn | ||||||
|  |  */ | ||||||
|  | void hal_gpio_init_ex( | ||||||
|  |     const GpioPin* gpio, | ||||||
|  |     const GpioMode mode, | ||||||
|  |     const GpioPull pull, | ||||||
|  |     const GpioSpeed speed, | ||||||
|  |     const GpioAltFn alt_fn); | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Add and enable interrupt | ||||||
|  |  * @param gpio GpioPin | ||||||
|  |  * @param cb   GpioExtiCallback | ||||||
|  |  * @param ctx  context for callback | ||||||
|  |  */ | ||||||
|  | void 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); | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Disable interrupt | ||||||
|  |  * @param gpio GpioPin | ||||||
|  |  */ | ||||||
|  | void hal_gpio_disable_int_callback(const GpioPin* gpio); | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Remove interrupt | ||||||
|  |  * @param gpio GpioPin | ||||||
|  |  */ | ||||||
|  | void 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) { | ||||||
|  |     // writing to BSSR is an atomic operation
 | ||||||
|  |     if(state == true) { | ||||||
|  |         gpio->port->BSRR = gpio->pin; | ||||||
|  |     } else { | ||||||
|  |         gpio->port->BSRR = (uint32_t)gpio->pin << GPIO_NUMBER; | ||||||
|  |     } | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * GPIO read pin | ||||||
|  |  * @param gpio GpioPin | ||||||
|  |  * @return true / false | ||||||
|  |  */ | ||||||
|  | static inline bool hal_gpio_read(const GpioPin* gpio) { | ||||||
|  |     if((gpio->port->IDR & gpio->pin) != 0x00U) { | ||||||
|  |         return true; | ||||||
|  |     } else { | ||||||
|  |         return false; | ||||||
|  |     } | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Get RFID IN level | ||||||
|  |  * @return false = LOW, true = HIGH | ||||||
|  |  */ | ||||||
|  | bool hal_gpio_get_rfid_in_level(); | ||||||
|  | 
 | ||||||
|  | #ifdef __cplusplus | ||||||
|  | } | ||||||
|  | #endif | ||||||
							
								
								
									
										41
									
								
								bootloader/targets/f6/furi-hal/furi-hal-resources.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								bootloader/targets/f6/furi-hal/furi-hal-resources.c
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,41 @@ | |||||||
|  | #include "furi-hal-resources.h" | ||||||
|  | #include "main.h" | ||||||
|  | 
 | ||||||
|  | const GpioPin vibro_gpio = {.port = VIBRO_GPIO_Port, .pin = VIBRO_Pin}; | ||||||
|  | const GpioPin ibutton_gpio = {.port = iBTN_GPIO_Port, .pin = iBTN_Pin}; | ||||||
|  | 
 | ||||||
|  | const GpioPin gpio_cc1101_g0 = {.port = CC1101_G0_GPIO_Port, .pin = CC1101_G0_Pin}; | ||||||
|  | const GpioPin gpio_rf_sw_0 = {.port = RF_SW_0_GPIO_Port, .pin = RF_SW_0_Pin}; | ||||||
|  | 
 | ||||||
|  | const GpioPin gpio_subghz_cs = {.port = CC1101_CS_GPIO_Port, .pin = CC1101_CS_Pin}; | ||||||
|  | const GpioPin gpio_display_cs = {.port = DISPLAY_CS_GPIO_Port, .pin = DISPLAY_CS_Pin}; | ||||||
|  | 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_nfc_cs = {.port = NFC_CS_GPIO_Port, .pin = NFC_CS_Pin}; | ||||||
|  | 
 | ||||||
|  | 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}; | ||||||
|  | const GpioPin gpio_spi_r_miso = {.port = SPI_R_MISO_GPIO_Port, .pin = SPI_R_MISO_Pin}; | ||||||
|  | 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 = 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}; | ||||||
|  | const GpioPin gpio_rfid_data_in = {.port = RFID_RF_IN_GPIO_Port, .pin = RFID_RF_IN_Pin}; | ||||||
|  | 
 | ||||||
|  | const GpioPin gpio_irda_rx = {.port = IR_RX_GPIO_Port, .pin = IR_RX_Pin}; | ||||||
|  | const GpioPin gpio_irda_tx = {.port = IR_TX_GPIO_Port, .pin = IR_TX_Pin}; | ||||||
|  | 
 | ||||||
|  | const GpioPin gpio_usart_tx = {.port = USART1_TX_Port, .pin = USART1_TX_Pin}; | ||||||
|  | const GpioPin gpio_usart_rx = {.port = USART1_RX_Port, .pin = USART1_RX_Pin}; | ||||||
| @ -2,6 +2,7 @@ | |||||||
| 
 | 
 | ||||||
| #include <stm32wbxx.h> | #include <stm32wbxx.h> | ||||||
| #include <stm32wbxx_ll_gpio.h> | #include <stm32wbxx_ll_gpio.h> | ||||||
|  | #include <furi-hal-gpio.h> | ||||||
| 
 | 
 | ||||||
| #ifdef __cplusplus | #ifdef __cplusplus | ||||||
| extern "C" { | extern "C" { | ||||||
| @ -37,6 +38,45 @@ typedef enum { | |||||||
|     LightBacklight, |     LightBacklight, | ||||||
| } Light; | } Light; | ||||||
| 
 | 
 | ||||||
|  | extern const GpioPin vibro_gpio; | ||||||
|  | extern const GpioPin ibutton_gpio; | ||||||
|  | 
 | ||||||
|  | extern const GpioPin gpio_cc1101_g0; | ||||||
|  | extern const GpioPin gpio_rf_sw_0; | ||||||
|  | 
 | ||||||
|  | extern const GpioPin gpio_subghz_cs; | ||||||
|  | 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_nfc_cs; | ||||||
|  | 
 | ||||||
|  | extern const GpioPin gpio_spi_d_miso; | ||||||
|  | extern const GpioPin gpio_spi_d_mosi; | ||||||
|  | extern const GpioPin gpio_spi_d_sck; | ||||||
|  | extern const GpioPin gpio_spi_r_miso; | ||||||
|  | extern const GpioPin gpio_spi_r_mosi; | ||||||
|  | extern const GpioPin gpio_spi_r_sck; | ||||||
|  | 
 | ||||||
|  | extern const GpioPin gpio_ext_pc0; | ||||||
|  | extern const GpioPin gpio_ext_pc1; | ||||||
|  | extern const GpioPin gpio_ext_pc3; | ||||||
|  | extern const GpioPin gpio_ext_pb2; | ||||||
|  | extern const GpioPin gpio_ext_pb3; | ||||||
|  | extern const GpioPin gpio_ext_pa4; | ||||||
|  | extern const GpioPin gpio_ext_pa6; | ||||||
|  | extern const GpioPin gpio_ext_pa7; | ||||||
|  | 
 | ||||||
|  | extern const GpioPin gpio_rfid_pull; | ||||||
|  | extern const GpioPin gpio_rfid_carrier_out; | ||||||
|  | extern const GpioPin gpio_rfid_data_in; | ||||||
|  | 
 | ||||||
|  | extern const GpioPin gpio_irda_rx; | ||||||
|  | extern const GpioPin gpio_irda_tx; | ||||||
|  | 
 | ||||||
|  | extern const GpioPin gpio_usart_tx; | ||||||
|  | extern const GpioPin gpio_usart_rx; | ||||||
|  | 
 | ||||||
| #ifdef __cplusplus | #ifdef __cplusplus | ||||||
| } | } | ||||||
| #endif | #endif | ||||||
|  | |||||||
							
								
								
									
										114
									
								
								bootloader/targets/f6/furi-hal/furi-hal-spi-config.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										114
									
								
								bootloader/targets/f6/furi-hal/furi-hal-spi-config.c
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,114 @@ | |||||||
|  | #include <furi-hal-spi-config.h> | ||||||
|  | #include <furi-hal-resources.h> | ||||||
|  | 
 | ||||||
|  | #define SPI_R SPI1 | ||||||
|  | #define SPI_D SPI2 | ||||||
|  | 
 | ||||||
|  | const LL_SPI_InitTypeDef furi_hal_spi_config_nfc = { | ||||||
|  |     .Mode = LL_SPI_MODE_MASTER, | ||||||
|  |     .TransferDirection = LL_SPI_FULL_DUPLEX, | ||||||
|  |     .DataWidth = LL_SPI_DATAWIDTH_8BIT, | ||||||
|  |     .ClockPolarity = LL_SPI_POLARITY_LOW, | ||||||
|  |     .ClockPhase = LL_SPI_PHASE_2EDGE, | ||||||
|  |     .NSS = LL_SPI_NSS_SOFT, | ||||||
|  |     .BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV8, | ||||||
|  |     .BitOrder = LL_SPI_MSB_FIRST, | ||||||
|  |     .CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE, | ||||||
|  |     .CRCPoly = 7, | ||||||
|  | }; | ||||||
|  | 
 | ||||||
|  | const LL_SPI_InitTypeDef furi_hal_spi_config_subghz = { | ||||||
|  |     .Mode = LL_SPI_MODE_MASTER, | ||||||
|  |     .TransferDirection = LL_SPI_FULL_DUPLEX, | ||||||
|  |     .DataWidth = LL_SPI_DATAWIDTH_8BIT, | ||||||
|  |     .ClockPolarity = LL_SPI_POLARITY_LOW, | ||||||
|  |     .ClockPhase = LL_SPI_PHASE_1EDGE, | ||||||
|  |     .NSS = LL_SPI_NSS_SOFT, | ||||||
|  |     .BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV8, | ||||||
|  |     .BitOrder = LL_SPI_MSB_FIRST, | ||||||
|  |     .CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE, | ||||||
|  |     .CRCPoly = 7, | ||||||
|  | }; | ||||||
|  | 
 | ||||||
|  | const LL_SPI_InitTypeDef furi_hal_spi_config_display = { | ||||||
|  |     .Mode = LL_SPI_MODE_MASTER, | ||||||
|  |     .TransferDirection = LL_SPI_FULL_DUPLEX, | ||||||
|  |     .DataWidth = LL_SPI_DATAWIDTH_8BIT, | ||||||
|  |     .ClockPolarity = LL_SPI_POLARITY_LOW, | ||||||
|  |     .ClockPhase = LL_SPI_PHASE_1EDGE, | ||||||
|  |     .NSS = LL_SPI_NSS_SOFT, | ||||||
|  |     .BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV16, | ||||||
|  |     .BitOrder = LL_SPI_MSB_FIRST, | ||||||
|  |     .CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE, | ||||||
|  |     .CRCPoly = 7, | ||||||
|  | }; | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * SD Card in fast mode (after init) | ||||||
|  |  */ | ||||||
|  | const LL_SPI_InitTypeDef furi_hal_spi_config_sd_fast = { | ||||||
|  |     .Mode = LL_SPI_MODE_MASTER, | ||||||
|  |     .TransferDirection = LL_SPI_FULL_DUPLEX, | ||||||
|  |     .DataWidth = LL_SPI_DATAWIDTH_8BIT, | ||||||
|  |     .ClockPolarity = LL_SPI_POLARITY_LOW, | ||||||
|  |     .ClockPhase = LL_SPI_PHASE_1EDGE, | ||||||
|  |     .NSS = LL_SPI_NSS_SOFT, | ||||||
|  |     .BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV2, | ||||||
|  |     .BitOrder = LL_SPI_MSB_FIRST, | ||||||
|  |     .CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE, | ||||||
|  |     .CRCPoly = 7, | ||||||
|  | }; | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * SD Card in slow mode (before init) | ||||||
|  |  */ | ||||||
|  | const LL_SPI_InitTypeDef furi_hal_spi_config_sd_slow = { | ||||||
|  |     .Mode = LL_SPI_MODE_MASTER, | ||||||
|  |     .TransferDirection = LL_SPI_FULL_DUPLEX, | ||||||
|  |     .DataWidth = LL_SPI_DATAWIDTH_8BIT, | ||||||
|  |     .ClockPolarity = LL_SPI_POLARITY_LOW, | ||||||
|  |     .ClockPhase = LL_SPI_PHASE_1EDGE, | ||||||
|  |     .NSS = LL_SPI_NSS_SOFT, | ||||||
|  |     .BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV32, | ||||||
|  |     .BitOrder = LL_SPI_MSB_FIRST, | ||||||
|  |     .CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE, | ||||||
|  |     .CRCPoly = 7, | ||||||
|  | }; | ||||||
|  | 
 | ||||||
|  | const FuriHalSpiBus spi_r = { | ||||||
|  |     .spi = SPI_R, | ||||||
|  |     .miso = &gpio_spi_r_miso, | ||||||
|  |     .mosi = &gpio_spi_r_mosi, | ||||||
|  |     .clk = &gpio_spi_r_sck, | ||||||
|  | }; | ||||||
|  | 
 | ||||||
|  | const FuriHalSpiBus spi_d = { | ||||||
|  |     .spi = SPI_D, | ||||||
|  |     .miso = &gpio_spi_d_miso, | ||||||
|  |     .mosi = &gpio_spi_d_mosi, | ||||||
|  |     .clk = &gpio_spi_d_sck, | ||||||
|  | }; | ||||||
|  | 
 | ||||||
|  | const FuriHalSpiDevice furi_hal_spi_devices[FuriHalSpiDeviceIdMax] = { | ||||||
|  |     { | ||||||
|  |         .bus = &spi_r, | ||||||
|  |         .config = &furi_hal_spi_config_subghz, | ||||||
|  |         .chip_select = &gpio_subghz_cs, | ||||||
|  |     }, | ||||||
|  |     { | ||||||
|  |         .bus = &spi_d, | ||||||
|  |         .config = &furi_hal_spi_config_display, | ||||||
|  |         .chip_select = &gpio_display_cs, | ||||||
|  |     }, | ||||||
|  |     { | ||||||
|  |         .bus = &spi_d, | ||||||
|  |         .config = &furi_hal_spi_config_sd_fast, | ||||||
|  |         .chip_select = &gpio_sdcard_cs, | ||||||
|  |     }, | ||||||
|  |     { | ||||||
|  |         .bus = &spi_d, | ||||||
|  |         .config = &furi_hal_spi_config_sd_slow, | ||||||
|  |         .chip_select = &gpio_sdcard_cs, | ||||||
|  |     }, | ||||||
|  |     {.bus = &spi_r, .config = &furi_hal_spi_config_nfc, .chip_select = &gpio_nfc_cs}, | ||||||
|  | }; | ||||||
							
								
								
									
										61
									
								
								bootloader/targets/f6/furi-hal/furi-hal-spi-config.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										61
									
								
								bootloader/targets/f6/furi-hal/furi-hal-spi-config.h
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,61 @@ | |||||||
|  | #pragma once | ||||||
|  | 
 | ||||||
|  | #include <furi-hal-gpio.h> | ||||||
|  | #include <stm32wbxx_ll_spi.h> | ||||||
|  | 
 | ||||||
|  | #ifdef __cplusplus | ||||||
|  | extern "C" { | ||||||
|  | #endif | ||||||
|  | 
 | ||||||
|  | extern const LL_SPI_InitTypeDef furi_hal_spi_config_nfc; | ||||||
|  | extern const LL_SPI_InitTypeDef furi_hal_spi_config_subghz; | ||||||
|  | extern const LL_SPI_InitTypeDef furi_hal_spi_config_display; | ||||||
|  | extern const LL_SPI_InitTypeDef furi_hal_spi_config_sd_fast; | ||||||
|  | extern const LL_SPI_InitTypeDef furi_hal_spi_config_sd_slow; | ||||||
|  | 
 | ||||||
|  | /** FURI HAL SPI BUS handler
 | ||||||
|  |  * Structure content may change at some point | ||||||
|  |  */ | ||||||
|  | typedef struct { | ||||||
|  |     const SPI_TypeDef* spi; | ||||||
|  |     const GpioPin* miso; | ||||||
|  |     const GpioPin* mosi; | ||||||
|  |     const GpioPin* clk; | ||||||
|  | } FuriHalSpiBus; | ||||||
|  | 
 | ||||||
|  | /** FURI HAL SPI Device handler
 | ||||||
|  |  * Structure content may change at some point | ||||||
|  |  */ | ||||||
|  | typedef struct { | ||||||
|  |     const FuriHalSpiBus* bus; | ||||||
|  |     const LL_SPI_InitTypeDef* config; | ||||||
|  |     const GpioPin* chip_select; | ||||||
|  | } FuriHalSpiDevice; | ||||||
|  | 
 | ||||||
|  | /** FURI HAL SPI Standard Device IDs */ | ||||||
|  | typedef enum { | ||||||
|  |     FuriHalSpiDeviceIdSubGhz, /** SubGhz: CC1101, non-standard SPI usage */ | ||||||
|  |     FuriHalSpiDeviceIdDisplay, /** Display: ERC12864, only have MOSI */ | ||||||
|  |     FuriHalSpiDeviceIdSdCardFast, /** SDCARD: fast mode, after initialization */ | ||||||
|  |     FuriHalSpiDeviceIdSdCardSlow, /** SDCARD: slow mode, before initialization */ | ||||||
|  |     FuriHalSpiDeviceIdNfc, /** NFC: ST25R3916, pretty standard, but RFAL makes it complex */ | ||||||
|  | 
 | ||||||
|  |     FuriHalSpiDeviceIdMax, /** Service Value, do not use */ | ||||||
|  | } FuriHalSpiDeviceId; | ||||||
|  | 
 | ||||||
|  | /** Furi Hal Spi Bus R
 | ||||||
|  |  * CC1101, Nfc | ||||||
|  |  */ | ||||||
|  | extern const FuriHalSpiBus spi_r; | ||||||
|  | 
 | ||||||
|  | /** Furi Hal Spi Bus D
 | ||||||
|  |  * Display, SdCard | ||||||
|  |  */ | ||||||
|  | extern const FuriHalSpiBus spi_d; | ||||||
|  | 
 | ||||||
|  | /** Furi Hal Spi devices */ | ||||||
|  | extern const FuriHalSpiDevice furi_hal_spi_devices[FuriHalSpiDeviceIdMax]; | ||||||
|  | 
 | ||||||
|  | #ifdef __cplusplus | ||||||
|  | } | ||||||
|  | #endif | ||||||
							
								
								
									
										240
									
								
								bootloader/targets/f6/furi-hal/furi-hal-spi.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										240
									
								
								bootloader/targets/f6/furi-hal/furi-hal-spi.c
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,240 @@ | |||||||
|  | #include "furi-hal-spi.h" | ||||||
|  | #include "furi-hal-resources.h" | ||||||
|  | 
 | ||||||
|  | #include <stdbool.h> | ||||||
|  | #include <assert.h> | ||||||
|  | 
 | ||||||
|  | #include <stm32wbxx_ll_spi.h> | ||||||
|  | #include <stm32wbxx_ll_utils.h> | ||||||
|  | #include <stm32wbxx_ll_cortex.h> | ||||||
|  | 
 | ||||||
|  | extern void Enable_SPI(SPI_TypeDef* spi); | ||||||
|  | 
 | ||||||
|  | void furi_hal_spi_init() { | ||||||
|  |     for(size_t i = 0; i < FuriHalSpiDeviceIdMax; ++i) { | ||||||
|  |         hal_gpio_write(furi_hal_spi_devices[i].chip_select, true); | ||||||
|  |         hal_gpio_init( | ||||||
|  |             furi_hal_spi_devices[i].chip_select, | ||||||
|  |             GpioModeOutputPushPull, | ||||||
|  |             GpioPullNo, | ||||||
|  |             GpioSpeedVeryHigh); | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     hal_gpio_init_ex( | ||||||
|  |         &gpio_spi_r_miso, | ||||||
|  |         GpioModeAltFunctionPushPull, | ||||||
|  |         GpioPullNo, | ||||||
|  |         GpioSpeedVeryHigh, | ||||||
|  |         GpioAltFn5SPI1); | ||||||
|  |     hal_gpio_init_ex( | ||||||
|  |         &gpio_spi_r_mosi, | ||||||
|  |         GpioModeAltFunctionPushPull, | ||||||
|  |         GpioPullNo, | ||||||
|  |         GpioSpeedVeryHigh, | ||||||
|  |         GpioAltFn5SPI1); | ||||||
|  |     hal_gpio_init_ex( | ||||||
|  |         &gpio_spi_r_sck, | ||||||
|  |         GpioModeAltFunctionPushPull, | ||||||
|  |         GpioPullNo, | ||||||
|  |         GpioSpeedVeryHigh, | ||||||
|  |         GpioAltFn5SPI1); | ||||||
|  | 
 | ||||||
|  |     hal_gpio_init_ex( | ||||||
|  |         &gpio_spi_d_miso, | ||||||
|  |         GpioModeAltFunctionPushPull, | ||||||
|  |         GpioPullUp, | ||||||
|  |         GpioSpeedVeryHigh, | ||||||
|  |         GpioAltFn5SPI2); | ||||||
|  |     hal_gpio_init_ex( | ||||||
|  |         &gpio_spi_d_mosi, | ||||||
|  |         GpioModeAltFunctionPushPull, | ||||||
|  |         GpioPullUp, | ||||||
|  |         GpioSpeedVeryHigh, | ||||||
|  |         GpioAltFn5SPI2); | ||||||
|  |     hal_gpio_init_ex( | ||||||
|  |         &gpio_spi_d_sck, | ||||||
|  |         GpioModeAltFunctionPushPull, | ||||||
|  |         GpioPullUp, | ||||||
|  |         GpioSpeedVeryHigh, | ||||||
|  |         GpioAltFn5SPI2); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void furi_hal_spi_bus_lock(const FuriHalSpiBus* bus) { | ||||||
|  |     assert(bus); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void furi_hal_spi_bus_unlock(const FuriHalSpiBus* bus) { | ||||||
|  |     assert(bus); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void furi_hal_spi_bus_configure(const FuriHalSpiBus* bus, const LL_SPI_InitTypeDef* config) { | ||||||
|  |     assert(bus); | ||||||
|  |     LL_SPI_DeInit((SPI_TypeDef*)bus->spi); | ||||||
|  |     LL_SPI_Init((SPI_TypeDef*)bus->spi, (LL_SPI_InitTypeDef*)config); | ||||||
|  |     LL_SPI_SetRxFIFOThreshold((SPI_TypeDef*)bus->spi, LL_SPI_RX_FIFO_TH_QUARTER); | ||||||
|  |     LL_SPI_Enable((SPI_TypeDef*)bus->spi); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void furi_hal_spi_bus_end_txrx(const FuriHalSpiBus* bus, uint32_t timeout) { | ||||||
|  |     while(LL_SPI_GetTxFIFOLevel((SPI_TypeDef*)bus->spi) != LL_SPI_TX_FIFO_EMPTY) | ||||||
|  |         ; | ||||||
|  |     while(LL_SPI_IsActiveFlag_BSY((SPI_TypeDef*)bus->spi)) | ||||||
|  |         ; | ||||||
|  |     while(LL_SPI_GetRxFIFOLevel((SPI_TypeDef*)bus->spi) != LL_SPI_RX_FIFO_EMPTY) { | ||||||
|  |         LL_SPI_ReceiveData8((SPI_TypeDef*)bus->spi); | ||||||
|  |     } | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | bool furi_hal_spi_bus_rx(const FuriHalSpiBus* bus, uint8_t* buffer, size_t size, uint32_t timeout) { | ||||||
|  |     assert(bus); | ||||||
|  |     assert(buffer); | ||||||
|  |     assert(size > 0); | ||||||
|  | 
 | ||||||
|  |     return furi_hal_spi_bus_trx(bus, buffer, buffer, size, timeout); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | bool furi_hal_spi_bus_tx(const FuriHalSpiBus* bus, uint8_t* buffer, size_t size, uint32_t timeout) { | ||||||
|  |     assert(bus); | ||||||
|  |     assert(buffer); | ||||||
|  |     assert(size > 0); | ||||||
|  |     bool ret = true; | ||||||
|  | 
 | ||||||
|  |     while(size > 0) { | ||||||
|  |         if(LL_SPI_IsActiveFlag_TXE((SPI_TypeDef*)bus->spi)) { | ||||||
|  |             LL_SPI_TransmitData8((SPI_TypeDef*)bus->spi, *buffer); | ||||||
|  |             buffer++; | ||||||
|  |             size--; | ||||||
|  |         } | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     furi_hal_spi_bus_end_txrx(bus, timeout); | ||||||
|  |     LL_SPI_ClearFlag_OVR((SPI_TypeDef*)bus->spi); | ||||||
|  | 
 | ||||||
|  |     return ret; | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | bool furi_hal_spi_bus_trx( | ||||||
|  |     const FuriHalSpiBus* bus, | ||||||
|  |     uint8_t* tx_buffer, | ||||||
|  |     uint8_t* rx_buffer, | ||||||
|  |     size_t size, | ||||||
|  |     uint32_t timeout) { | ||||||
|  |     assert(bus); | ||||||
|  |     assert(tx_buffer); | ||||||
|  |     assert(rx_buffer); | ||||||
|  |     assert(size > 0); | ||||||
|  |     bool ret = true; | ||||||
|  |     size_t tx_size = size; | ||||||
|  |     bool tx_allowed = true; | ||||||
|  | 
 | ||||||
|  |     while(size > 0) { | ||||||
|  |         if(tx_size > 0 && LL_SPI_IsActiveFlag_TXE((SPI_TypeDef*)bus->spi) && tx_allowed) { | ||||||
|  |             LL_SPI_TransmitData8((SPI_TypeDef*)bus->spi, *tx_buffer); | ||||||
|  |             tx_buffer++; | ||||||
|  |             tx_size--; | ||||||
|  |             tx_allowed = false; | ||||||
|  |         } | ||||||
|  | 
 | ||||||
|  |         if(LL_SPI_IsActiveFlag_RXNE((SPI_TypeDef*)bus->spi)) { | ||||||
|  |             *rx_buffer = LL_SPI_ReceiveData8((SPI_TypeDef*)bus->spi); | ||||||
|  |             rx_buffer++; | ||||||
|  |             size--; | ||||||
|  |             tx_allowed = true; | ||||||
|  |         } | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     furi_hal_spi_bus_end_txrx(bus, timeout); | ||||||
|  | 
 | ||||||
|  |     return ret; | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void furi_hal_spi_device_configure(const FuriHalSpiDevice* device) { | ||||||
|  |     assert(device); | ||||||
|  |     assert(device->config); | ||||||
|  | 
 | ||||||
|  |     furi_hal_spi_bus_configure(device->bus, device->config); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | const FuriHalSpiDevice* furi_hal_spi_device_get(FuriHalSpiDeviceId device_id) { | ||||||
|  |     assert(device_id < FuriHalSpiDeviceIdMax); | ||||||
|  | 
 | ||||||
|  |     const FuriHalSpiDevice* device = &furi_hal_spi_devices[device_id]; | ||||||
|  |     assert(device); | ||||||
|  | 
 | ||||||
|  |     furi_hal_spi_bus_lock(device->bus); | ||||||
|  |     furi_hal_spi_device_configure(device); | ||||||
|  | 
 | ||||||
|  |     return device; | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void furi_hal_spi_device_return(const FuriHalSpiDevice* device) { | ||||||
|  |     furi_hal_spi_bus_unlock(device->bus); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | bool furi_hal_spi_device_rx( | ||||||
|  |     const FuriHalSpiDevice* device, | ||||||
|  |     uint8_t* buffer, | ||||||
|  |     size_t size, | ||||||
|  |     uint32_t timeout) { | ||||||
|  |     assert(device); | ||||||
|  |     assert(buffer); | ||||||
|  |     assert(size > 0); | ||||||
|  | 
 | ||||||
|  |     if(device->chip_select) { | ||||||
|  |         hal_gpio_write(device->chip_select, false); | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     bool ret = furi_hal_spi_bus_rx(device->bus, buffer, size, timeout); | ||||||
|  | 
 | ||||||
|  |     if(device->chip_select) { | ||||||
|  |         hal_gpio_write(device->chip_select, true); | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     return ret; | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | bool furi_hal_spi_device_tx( | ||||||
|  |     const FuriHalSpiDevice* device, | ||||||
|  |     uint8_t* buffer, | ||||||
|  |     size_t size, | ||||||
|  |     uint32_t timeout) { | ||||||
|  |     assert(device); | ||||||
|  |     assert(buffer); | ||||||
|  |     assert(size > 0); | ||||||
|  | 
 | ||||||
|  |     if(device->chip_select) { | ||||||
|  |         hal_gpio_write(device->chip_select, false); | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     bool ret = furi_hal_spi_bus_tx(device->bus, buffer, size, timeout); | ||||||
|  | 
 | ||||||
|  |     if(device->chip_select) { | ||||||
|  |         hal_gpio_write(device->chip_select, true); | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     return ret; | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | bool furi_hal_spi_device_trx( | ||||||
|  |     const FuriHalSpiDevice* device, | ||||||
|  |     uint8_t* tx_buffer, | ||||||
|  |     uint8_t* rx_buffer, | ||||||
|  |     size_t size, | ||||||
|  |     uint32_t timeout) { | ||||||
|  |     assert(device); | ||||||
|  |     assert(tx_buffer); | ||||||
|  |     assert(rx_buffer); | ||||||
|  |     assert(size > 0); | ||||||
|  | 
 | ||||||
|  |     if(device->chip_select) { | ||||||
|  |         hal_gpio_write(device->chip_select, false); | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     bool ret = furi_hal_spi_bus_trx(device->bus, tx_buffer, rx_buffer, size, timeout); | ||||||
|  | 
 | ||||||
|  |     if(device->chip_select) { | ||||||
|  |         hal_gpio_write(device->chip_select, true); | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     return ret; | ||||||
|  | } | ||||||
							
								
								
									
										129
									
								
								bootloader/targets/f6/furi-hal/furi-hal-spi.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										129
									
								
								bootloader/targets/f6/furi-hal/furi-hal-spi.h
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,129 @@ | |||||||
|  | #pragma once | ||||||
|  | 
 | ||||||
|  | #include "main.h" | ||||||
|  | 
 | ||||||
|  | #include "furi-hal-spi-config.h" | ||||||
|  | #include <furi-hal-gpio.h> | ||||||
|  | 
 | ||||||
|  | #include <stdbool.h> | ||||||
|  | #include <stddef.h> | ||||||
|  | 
 | ||||||
|  | #ifdef __cplusplus | ||||||
|  | extern "C" { | ||||||
|  | #endif | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Init SPI API | ||||||
|  |  */ | ||||||
|  | void furi_hal_spi_init(); | ||||||
|  | 
 | ||||||
|  | /* Bus Level API */ | ||||||
|  | 
 | ||||||
|  | /** Lock SPI bus
 | ||||||
|  |  * Takes bus mutex, if used | ||||||
|  |  */ | ||||||
|  | void furi_hal_spi_bus_lock(const FuriHalSpiBus* bus); | ||||||
|  | 
 | ||||||
|  | /** Unlock SPI bus
 | ||||||
|  |  * Releases BUS mutex, if used | ||||||
|  |  */ | ||||||
|  | void furi_hal_spi_bus_unlock(const FuriHalSpiBus* bus); | ||||||
|  | 
 | ||||||
|  | /**
 | ||||||
|  |  * Configure SPI bus | ||||||
|  |  * @param bus - spi bus handler | ||||||
|  |  * @param config - spi configuration structure | ||||||
|  |  */ | ||||||
|  | void furi_hal_spi_bus_configure(const FuriHalSpiBus* bus, const LL_SPI_InitTypeDef* config); | ||||||
|  | 
 | ||||||
|  | /** SPI Receive
 | ||||||
|  |  * @param bus - spi bus handler | ||||||
|  |  * @param buffer - receive buffer | ||||||
|  |  * @param size - transaction size | ||||||
|  |  * @param timeout - bus operation timeout in ms | ||||||
|  |  */ | ||||||
|  | bool furi_hal_spi_bus_rx(const FuriHalSpiBus* bus, uint8_t* buffer, size_t size, uint32_t timeout); | ||||||
|  | 
 | ||||||
|  | /** SPI Transmit
 | ||||||
|  |  * @param bus - spi bus handler | ||||||
|  |  * @param buffer - transmit buffer | ||||||
|  |  * @param size - transaction size | ||||||
|  |  * @param timeout - bus operation timeout in ms | ||||||
|  |  */ | ||||||
|  | bool furi_hal_spi_bus_tx(const FuriHalSpiBus* bus, uint8_t* buffer, size_t size, uint32_t timeout); | ||||||
|  | 
 | ||||||
|  | /** SPI Transmit and Receive
 | ||||||
|  |  * @param bus - spi bus handlere | ||||||
|  |  * @param tx_buffer - device handle | ||||||
|  |  * @param rx_buffer - device handle | ||||||
|  |  * @param size - transaction size | ||||||
|  |  * @param timeout - bus operation timeout in ms | ||||||
|  |  */ | ||||||
|  | bool furi_hal_spi_bus_trx( | ||||||
|  |     const FuriHalSpiBus* bus, | ||||||
|  |     uint8_t* tx_buffer, | ||||||
|  |     uint8_t* rx_buffer, | ||||||
|  |     size_t size, | ||||||
|  |     uint32_t timeout); | ||||||
|  | 
 | ||||||
|  | /* Device Level API */ | ||||||
|  | 
 | ||||||
|  | /** Reconfigure SPI bus for device
 | ||||||
|  |  * @param device - device description | ||||||
|  |  */ | ||||||
|  | void furi_hal_spi_device_configure(const FuriHalSpiDevice* device); | ||||||
|  | 
 | ||||||
|  | /** Get Device handle
 | ||||||
|  |  * And lock access to the corresponding SPI BUS | ||||||
|  |  * @param device_id - device identifier | ||||||
|  |  * @return device handle | ||||||
|  |  */ | ||||||
|  | const FuriHalSpiDevice* furi_hal_spi_device_get(FuriHalSpiDeviceId device_id); | ||||||
|  | 
 | ||||||
|  | /** Return Device handle
 | ||||||
|  |  * And unlock access to the corresponding SPI BUS | ||||||
|  |  * @param device - device handle | ||||||
|  |  */ | ||||||
|  | void furi_hal_spi_device_return(const FuriHalSpiDevice* device); | ||||||
|  | 
 | ||||||
|  | /** SPI Recieve
 | ||||||
|  |  * @param device - device handle | ||||||
|  |  * @param buffer - receive buffer | ||||||
|  |  * @param size - transaction size | ||||||
|  |  * @param timeout - bus operation timeout in ms | ||||||
|  |  */ | ||||||
|  | bool furi_hal_spi_device_rx( | ||||||
|  |     const FuriHalSpiDevice* device, | ||||||
|  |     uint8_t* buffer, | ||||||
|  |     size_t size, | ||||||
|  |     uint32_t timeout); | ||||||
|  | 
 | ||||||
|  | /** SPI Transmit
 | ||||||
|  |  * @param device - device handle | ||||||
|  |  * @param buffer - transmit buffer | ||||||
|  |  * @param size - transaction size | ||||||
|  |  * @param timeout - bus operation timeout in ms | ||||||
|  |  */ | ||||||
|  | bool furi_hal_spi_device_tx( | ||||||
|  |     const FuriHalSpiDevice* device, | ||||||
|  |     uint8_t* buffer, | ||||||
|  |     size_t size, | ||||||
|  |     uint32_t timeout); | ||||||
|  | 
 | ||||||
|  | /** SPI Transmit and Receive
 | ||||||
|  |  * @param device - device handle | ||||||
|  |  * @param tx_buffer - device handle | ||||||
|  |  * @param rx_buffer - device handle | ||||||
|  |  * @param size - transaction size | ||||||
|  |  * @param timeout - bus operation timeout in ms | ||||||
|  |  */ | ||||||
|  | bool furi_hal_spi_device_trx( | ||||||
|  |     const FuriHalSpiDevice* device, | ||||||
|  |     uint8_t* tx_buffer, | ||||||
|  |     uint8_t* rx_buffer, | ||||||
|  |     size_t size, | ||||||
|  |     uint32_t timeout); | ||||||
|  | 
 | ||||||
|  | #ifdef __cplusplus | ||||||
|  | } | ||||||
|  | #endif | ||||||
| @ -3,4 +3,5 @@ | |||||||
| void furi_hal_init() { | void furi_hal_init() { | ||||||
|     furi_hal_i2c_init(); |     furi_hal_i2c_init(); | ||||||
|     furi_hal_light_init(); |     furi_hal_light_init(); | ||||||
|  |     furi_hal_spi_init(); | ||||||
| } | } | ||||||
| @ -2,5 +2,7 @@ | |||||||
| 
 | 
 | ||||||
| #include <furi-hal-i2c.h> | #include <furi-hal-i2c.h> | ||||||
| #include <furi-hal-light.h> | #include <furi-hal-light.h> | ||||||
|  | #include <furi-hal-resources.h> | ||||||
|  | #include <furi-hal-spi.h> | ||||||
| 
 | 
 | ||||||
| void furi_hal_init(); | void furi_hal_init(); | ||||||
							
								
								
									
										108
									
								
								bootloader/targets/f6/furi-hal/main.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										108
									
								
								bootloader/targets/f6/furi-hal/main.h
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,108 @@ | |||||||
|  | #pragma once | ||||||
|  | 
 | ||||||
|  | #include <stm32wbxx.h> | ||||||
|  | #include <stm32wbxx_ll_gpio.h> | ||||||
|  | #include <stm32wbxx_ll_spi.h> | ||||||
|  | 
 | ||||||
|  | #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_TUNE_GPIO_Port GPIOA | ||||||
|  | #define RFID_TUNE_Pin LL_GPIO_PIN_8 | ||||||
|  | 
 | ||||||
|  | #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_15 | ||||||
|  | 
 | ||||||
|  | #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 | ||||||
							
								
								
									
										69
									
								
								bootloader/targets/f6/furi-hal/u8g2_periphery.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										69
									
								
								bootloader/targets/f6/furi-hal/u8g2_periphery.c
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,69 @@ | |||||||
|  | #include <u8g2.h> | ||||||
|  | #include <assert.h> | ||||||
|  | #include <furi-hal.h> | ||||||
|  | #include <stm32wbxx_ll_utils.h> | ||||||
|  | 
 | ||||||
|  | static FuriHalSpiDevice* u8g2_periphery_display = NULL; | ||||||
|  | 
 | ||||||
|  | uint8_t u8g2_gpio_and_delay_stm32(u8x8_t* u8x8, uint8_t msg, uint8_t arg_int, void* arg_ptr) { | ||||||
|  |     switch(msg) { | ||||||
|  |     case U8X8_MSG_GPIO_AND_DELAY_INIT: | ||||||
|  |         /* HAL initialization contains all what we need so we can skip this part. */ | ||||||
|  |         break; | ||||||
|  | 
 | ||||||
|  |     case U8X8_MSG_DELAY_MILLI: | ||||||
|  |         LL_mDelay(arg_int); | ||||||
|  |         break; | ||||||
|  | 
 | ||||||
|  |     case U8X8_MSG_DELAY_10MICRO: | ||||||
|  |         LL_mDelay(1); | ||||||
|  |         break; | ||||||
|  | 
 | ||||||
|  |     case U8X8_MSG_DELAY_100NANO: | ||||||
|  |         asm("nop"); | ||||||
|  |         break; | ||||||
|  | 
 | ||||||
|  |     case U8X8_MSG_GPIO_RESET: | ||||||
|  |         hal_gpio_write(&gpio_display_rst, arg_int); | ||||||
|  |         break; | ||||||
|  | 
 | ||||||
|  |     default: | ||||||
|  |         return 0; | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     return 1; | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | uint8_t u8x8_hw_spi_stm32(u8x8_t* u8x8, uint8_t msg, uint8_t arg_int, void* arg_ptr) { | ||||||
|  |     switch(msg) { | ||||||
|  |     case U8X8_MSG_BYTE_SEND: | ||||||
|  |         furi_hal_spi_bus_tx(u8g2_periphery_display->bus, (uint8_t*)arg_ptr, arg_int, 10000); | ||||||
|  |         break; | ||||||
|  | 
 | ||||||
|  |     case U8X8_MSG_BYTE_SET_DC: | ||||||
|  |         hal_gpio_write(&gpio_display_di, arg_int); | ||||||
|  |         break; | ||||||
|  | 
 | ||||||
|  |     case U8X8_MSG_BYTE_INIT: | ||||||
|  |         break; | ||||||
|  | 
 | ||||||
|  |     case U8X8_MSG_BYTE_START_TRANSFER: | ||||||
|  |         assert(u8g2_periphery_display == NULL); | ||||||
|  |         u8g2_periphery_display = | ||||||
|  |             (FuriHalSpiDevice*)furi_hal_spi_device_get(FuriHalSpiDeviceIdDisplay); | ||||||
|  |         hal_gpio_write(u8g2_periphery_display->chip_select, false); | ||||||
|  |         break; | ||||||
|  | 
 | ||||||
|  |     case U8X8_MSG_BYTE_END_TRANSFER: | ||||||
|  |         assert(u8g2_periphery_display); | ||||||
|  |         hal_gpio_write(u8g2_periphery_display->chip_select, true); | ||||||
|  |         furi_hal_spi_device_return(u8g2_periphery_display); | ||||||
|  |         u8g2_periphery_display = NULL; | ||||||
|  |         break; | ||||||
|  | 
 | ||||||
|  |     default: | ||||||
|  |         return 0; | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     return 1; | ||||||
|  | } | ||||||
| @ -11,6 +11,16 @@ | |||||||
| 
 | 
 | ||||||
| #include <lib/toolbox/version.h> | #include <lib/toolbox/version.h> | ||||||
| #include <furi-hal.h> | #include <furi-hal.h> | ||||||
|  | #include <u8g2.h> | ||||||
|  | 
 | ||||||
|  | const uint8_t I_Warning_30x23_0[] = { | ||||||
|  |     0x00, 0xC0, 0x00, 0x00, 0x00, 0xE0, 0x01, 0x00, 0x00, 0xF0, 0x03, 0x00, 0x00, 0xF0, 0x03, 0x00, | ||||||
|  |     0x00, 0xF8, 0x07, 0x00, 0x00, 0x3C, 0x0F, 0x00, 0x00, 0x3C, 0x0F, 0x00, 0x00, 0x3E, 0x1F, 0x00, | ||||||
|  |     0x00, 0x3F, 0x3F, 0x00, 0x00, 0x3F, 0x3F, 0x00, 0x80, 0x3F, 0x7F, 0x00, 0xC0, 0x3F, 0xFF, 0x00, | ||||||
|  |     0xC0, 0x3F, 0xFF, 0x00, 0xE0, 0x3F, 0xFF, 0x01, 0xF0, 0x3F, 0xFF, 0x03, 0xF0, 0x3F, 0xFF, 0x03, | ||||||
|  |     0xF8, 0x3F, 0xFF, 0x07, 0xFC, 0xFF, 0xFF, 0x0F, 0xFC, 0xFF, 0xFF, 0x0F, 0xFE, 0x3F, 0xFF, 0x1F, | ||||||
|  |     0xFF, 0x3F, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x3F, 0xFE, 0xFF, 0xFF, 0x1F, | ||||||
|  | }; | ||||||
| 
 | 
 | ||||||
| // Boot request enum
 | // Boot request enum
 | ||||||
| #define BOOT_REQUEST_TAINTED 0x00000000 | #define BOOT_REQUEST_TAINTED 0x00000000 | ||||||
| @ -27,6 +37,9 @@ | |||||||
| 
 | 
 | ||||||
| #define RTC_CLOCK_IS_READY() (LL_RCC_LSE_IsReady() && LL_RCC_LSI1_IsReady()) | #define RTC_CLOCK_IS_READY() (LL_RCC_LSE_IsReady() && LL_RCC_LSI1_IsReady()) | ||||||
| 
 | 
 | ||||||
|  | uint8_t u8g2_gpio_and_delay_stm32(u8x8_t* u8x8, uint8_t msg, uint8_t arg_int, void* arg_ptr); | ||||||
|  | uint8_t u8x8_hw_spi_stm32(u8x8_t* u8x8, uint8_t msg, uint8_t arg_int, void* arg_ptr); | ||||||
|  | 
 | ||||||
| void target_led_control(char* c) { | void target_led_control(char* c) { | ||||||
|     furi_hal_light_set(LightRed, 0x00); |     furi_hal_light_set(LightRed, 0x00); | ||||||
|     furi_hal_light_set(LightGreen, 0x00); |     furi_hal_light_set(LightGreen, 0x00); | ||||||
| @ -59,15 +72,22 @@ void target_led_control(char* c) { | |||||||
|     } while(*c != 0); |     } while(*c != 0); | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void clock_init() { | void target_clock_init() { | ||||||
|     LL_Init1msTick(4000000); |     LL_Init1msTick(4000000); | ||||||
|     LL_SetSystemCoreClock(4000000); |     LL_SetSystemCoreClock(4000000); | ||||||
| } |  | ||||||
| 
 | 
 | ||||||
| void gpio_init() { |  | ||||||
|     LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOA); |     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_GPIOB); | ||||||
|     LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOC); |     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); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void target_gpio_init() { | ||||||
|     // USB D+
 |     // USB D+
 | ||||||
|     LL_GPIO_SetPinMode(BOOT_USB_PORT, BOOT_USB_DP_PIN, LL_GPIO_MODE_OUTPUT); |     LL_GPIO_SetPinMode(BOOT_USB_PORT, BOOT_USB_DP_PIN, LL_GPIO_MODE_OUTPUT); | ||||||
|     LL_GPIO_SetPinSpeed(BOOT_USB_PORT, BOOT_USB_DP_PIN, LL_GPIO_SPEED_FREQ_VERY_HIGH); |     LL_GPIO_SetPinSpeed(BOOT_USB_PORT, BOOT_USB_DP_PIN, LL_GPIO_SPEED_FREQ_VERY_HIGH); | ||||||
| @ -81,7 +101,7 @@ void gpio_init() { | |||||||
|     LL_GPIO_SetPinPull(BOOT_DFU_PORT, BOOT_DFU_PIN, LL_GPIO_PULL_UP); |     LL_GPIO_SetPinPull(BOOT_DFU_PORT, BOOT_DFU_PIN, LL_GPIO_PULL_UP); | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void rtc_init() { | void target_rtc_init() { | ||||||
|     // LSE and RTC
 |     // LSE and RTC
 | ||||||
|     LL_PWR_EnableBkUpAccess(); |     LL_PWR_EnableBkUpAccess(); | ||||||
|     if(!RTC_CLOCK_IS_READY()) { |     if(!RTC_CLOCK_IS_READY()) { | ||||||
| @ -112,24 +132,46 @@ void rtc_init() { | |||||||
|     LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_RTCAPB); |     LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_RTCAPB); | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void version_save(void) { | void target_version_save(void) { | ||||||
|     LL_RTC_BAK_SetRegister(RTC, LL_RTC_BKP_DR1, (uint32_t)version_get()); |     LL_RTC_BAK_SetRegister(RTC, LL_RTC_BKP_DR1, (uint32_t)version_get()); | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void usb_wire_reset() { | void target_usb_wire_reset() { | ||||||
|     LL_GPIO_ResetOutputPin(BOOT_USB_PORT, BOOT_USB_PIN); |     LL_GPIO_ResetOutputPin(BOOT_USB_PORT, BOOT_USB_PIN); | ||||||
|     LL_mDelay(10); |     LL_mDelay(10); | ||||||
|     LL_GPIO_SetOutputPin(BOOT_USB_PORT, BOOT_USB_PIN); |     LL_GPIO_SetOutputPin(BOOT_USB_PORT, BOOT_USB_PIN); | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
|  | void target_display_init() { | ||||||
|  |     // Prepare gpio
 | ||||||
|  |     hal_gpio_init_simple(&gpio_display_rst, GpioModeOutputPushPull); | ||||||
|  |     hal_gpio_init_simple(&gpio_display_di, GpioModeOutputPushPull); | ||||||
|  |     // Initialize
 | ||||||
|  |     u8g2_t fb; | ||||||
|  |     u8g2_Setup_st7565_erc12864_alt_f(&fb, U8G2_R0, u8x8_hw_spi_stm32, u8g2_gpio_and_delay_stm32); | ||||||
|  |     u8g2_InitDisplay(&fb); | ||||||
|  |     u8g2_SetContrast(&fb, 36); | ||||||
|  |     // Create payload
 | ||||||
|  |     u8g2_ClearBuffer(&fb); | ||||||
|  |     u8g2_SetDrawColor(&fb, 0x01); | ||||||
|  |     u8g2_SetFont(&fb, u8g2_font_helvB08_tf); | ||||||
|  |     u8g2_DrawStr(&fb, 2, 8, "Recovery & Update Mode"); | ||||||
|  |     u8g2_DrawXBM(&fb, 49, 14, 30, 23, I_Warning_30x23_0); | ||||||
|  |     u8g2_DrawStr(&fb, 2, 50, "DFU Bootloader activated"); | ||||||
|  |     u8g2_DrawStr(&fb, 6, 62, "www.flipp.dev/recovery"); | ||||||
|  |     // Send buffer
 | ||||||
|  |     u8g2_SetPowerSave(&fb, 0); | ||||||
|  |     u8g2_SendBuffer(&fb); | ||||||
|  | } | ||||||
|  | 
 | ||||||
| void target_init() { | void target_init() { | ||||||
|     clock_init(); |     target_clock_init(); | ||||||
|     gpio_init(); |     target_gpio_init(); | ||||||
|     furi_hal_init(); |     furi_hal_init(); | ||||||
|     target_led_control("RGB"); |     target_led_control("RGB"); | ||||||
|     rtc_init(); |     target_rtc_init(); | ||||||
|     version_save(); |     target_version_save(); | ||||||
|     usb_wire_reset(); |     target_usb_wire_reset(); | ||||||
| 
 | 
 | ||||||
|     // Errata 2.2.9, Flash OPTVERR flag is always set after system reset
 |     // Errata 2.2.9, Flash OPTVERR flag is always set after system reset
 | ||||||
|     __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_ALL_ERRORS); |     __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_ALL_ERRORS); | ||||||
| @ -164,10 +206,13 @@ void target_switch(void* offset) { | |||||||
| 
 | 
 | ||||||
| void target_switch2dfu() { | void target_switch2dfu() { | ||||||
|     target_led_control("B"); |     target_led_control("B"); | ||||||
|  |     furi_hal_light_set(LightBacklight, 0xFF); | ||||||
|  |     target_display_init(); | ||||||
|     // Mark system as tainted, it will be soon
 |     // Mark system as tainted, it will be soon
 | ||||||
|     LL_RTC_BAK_SetRegister(RTC, LL_RTC_BKP_DR0, BOOT_REQUEST_TAINTED); |     LL_RTC_BAK_SetRegister(RTC, LL_RTC_BKP_DR0, BOOT_REQUEST_TAINTED); | ||||||
|     // Remap memory to system bootloader
 |     // Remap memory to system bootloader
 | ||||||
|     LL_SYSCFG_SetRemapMemory(LL_SYSCFG_REMAP_SYSTEMFLASH); |     LL_SYSCFG_SetRemapMemory(LL_SYSCFG_REMAP_SYSTEMFLASH); | ||||||
|  |     // Jump
 | ||||||
|     target_switch(0x0); |     target_switch(0x0); | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
|  | |||||||
| @ -21,6 +21,7 @@ C_SOURCES		+= $(CUBE_DIR)/Drivers/CMSIS/Device/ST/STM32WBxx/Source/Templates/sys | |||||||
| C_SOURCES		+= $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_utils.c | C_SOURCES		+= $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_utils.c | ||||||
| C_SOURCES		+= $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_gpio.c | C_SOURCES		+= $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_gpio.c | ||||||
| C_SOURCES		+= $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_i2c.c | C_SOURCES		+= $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_i2c.c | ||||||
|  | C_SOURCES		+= $(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_spi.c | ||||||
| 
 | 
 | ||||||
| CFLAGS			+= -I$(CUBE_DIR)/Drivers/CMSIS/Include | CFLAGS			+= -I$(CUBE_DIR)/Drivers/CMSIS/Include | ||||||
| CFLAGS			+= -I$(CUBE_DIR)/Drivers/CMSIS/Device/ST/STM32WBxx/Include | CFLAGS			+= -I$(CUBE_DIR)/Drivers/CMSIS/Device/ST/STM32WBxx/Include | ||||||
|  | |||||||
| @ -1,52 +0,0 @@ | |||||||
| /**
 |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @file    adc.h |  | ||||||
|   * @brief   This file contains all the function prototypes for |  | ||||||
|   *          the adc.c file |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @attention |  | ||||||
|   * |  | ||||||
|   * <h2><center>© 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 __ADC_H__ |  | ||||||
| #define __ADC_H__ |  | ||||||
| 
 |  | ||||||
| #ifdef __cplusplus |  | ||||||
| extern "C" { |  | ||||||
| #endif |  | ||||||
| 
 |  | ||||||
| /* Includes ------------------------------------------------------------------*/ |  | ||||||
| #include "main.h" |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN Includes */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END Includes */ |  | ||||||
| 
 |  | ||||||
| extern ADC_HandleTypeDef hadc1; |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN Private defines */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END Private defines */ |  | ||||||
| 
 |  | ||||||
| void MX_ADC1_Init(void); |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN Prototypes */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END Prototypes */ |  | ||||||
| 
 |  | ||||||
| #ifdef __cplusplus |  | ||||||
| } |  | ||||||
| #endif |  | ||||||
| 
 |  | ||||||
| #endif /* __ADC_H__ */ |  | ||||||
| 
 |  | ||||||
| /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |  | ||||||
| @ -1,52 +0,0 @@ | |||||||
| /**
 |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @file    crc.h |  | ||||||
|   * @brief   This file contains all the function prototypes for |  | ||||||
|   *          the crc.c file |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @attention |  | ||||||
|   * |  | ||||||
|   * <h2><center>© 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 __CRC_H__ |  | ||||||
| #define __CRC_H__ |  | ||||||
| 
 |  | ||||||
| #ifdef __cplusplus |  | ||||||
| extern "C" { |  | ||||||
| #endif |  | ||||||
| 
 |  | ||||||
| /* Includes ------------------------------------------------------------------*/ |  | ||||||
| #include "main.h" |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN Includes */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END Includes */ |  | ||||||
| 
 |  | ||||||
| extern CRC_HandleTypeDef hcrc; |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN Private defines */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END Private defines */ |  | ||||||
| 
 |  | ||||||
| void MX_CRC_Init(void); |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN Prototypes */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END Prototypes */ |  | ||||||
| 
 |  | ||||||
| #ifdef __cplusplus |  | ||||||
| } |  | ||||||
| #endif |  | ||||||
| 
 |  | ||||||
| #endif /* __CRC_H__ */ |  | ||||||
| 
 |  | ||||||
| /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |  | ||||||
| @ -117,10 +117,6 @@ void Error_Handler(void); | |||||||
| #define SPI_R_SCK_GPIO_Port GPIOA | #define SPI_R_SCK_GPIO_Port GPIOA | ||||||
| #define SPI_R_SCK_Pin GPIO_PIN_5 | #define SPI_R_SCK_Pin GPIO_PIN_5 | ||||||
| 
 | 
 | ||||||
| #define SPI_R hspi1 |  | ||||||
| #define SPI_D hspi2 |  | ||||||
| #define SPI_SD_HANDLE SPI_D |  | ||||||
| 
 |  | ||||||
| extern TIM_HandleTypeDef htim1; | extern TIM_HandleTypeDef htim1; | ||||||
| extern TIM_HandleTypeDef htim2; | extern TIM_HandleTypeDef htim2; | ||||||
| extern TIM_HandleTypeDef htim16; | extern TIM_HandleTypeDef htim16; | ||||||
|  | |||||||
| @ -1,59 +0,0 @@ | |||||||
| /**
 |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @file    spi.h |  | ||||||
|   * @brief   This file contains all the function prototypes for |  | ||||||
|   *          the spi.c file |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @attention |  | ||||||
|   * |  | ||||||
|   * <h2><center>© 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 __SPI_H__ |  | ||||||
| #define __SPI_H__ |  | ||||||
| 
 |  | ||||||
| #ifdef __cplusplus |  | ||||||
| extern "C" { |  | ||||||
| #endif |  | ||||||
| 
 |  | ||||||
| /* Includes ------------------------------------------------------------------*/ |  | ||||||
| #include "main.h" |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN Includes */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END Includes */ |  | ||||||
| 
 |  | ||||||
| extern SPI_HandleTypeDef hspi1; |  | ||||||
| extern SPI_HandleTypeDef hspi2; |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN Private defines */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END Private defines */ |  | ||||||
| 
 |  | ||||||
| void MX_SPI1_Init(void); |  | ||||||
| void MX_SPI2_Init(void); |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN Prototypes */ |  | ||||||
| void NFC_SPI_Reconfigure(); |  | ||||||
| void SD_SPI_Reconfigure_Slow(); |  | ||||||
| void SD_SPI_Reconfigure_Fast(); |  | ||||||
| void CC1101_SPI_Reconfigure(); |  | ||||||
| void SD_SPI_Bus_To_Down_State(); |  | ||||||
| void SD_SPI_Bus_To_Normal_State(); |  | ||||||
| /* USER CODE END Prototypes */ |  | ||||||
| 
 |  | ||||||
| #ifdef __cplusplus |  | ||||||
| } |  | ||||||
| #endif |  | ||||||
| 
 |  | ||||||
| #endif /* __SPI_H__ */ |  | ||||||
| 
 |  | ||||||
| /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |  | ||||||
| @ -33,30 +33,30 @@ | |||||||
|   * @brief This is the list of modules to be used in the HAL driver |   * @brief This is the list of modules to be used in the HAL driver | ||||||
|   */ |   */ | ||||||
| #define HAL_MODULE_ENABLED | #define HAL_MODULE_ENABLED | ||||||
| #define HAL_ADC_MODULE_ENABLED | /*#define HAL_ADC_MODULE_ENABLED    */ | ||||||
| #define HAL_CRYP_MODULE_ENABLED | #define HAL_CRYP_MODULE_ENABLED | ||||||
| #define HAL_COMP_MODULE_ENABLED | #define HAL_COMP_MODULE_ENABLED | ||||||
| #define HAL_CRC_MODULE_ENABLED | /*#define HAL_CRC_MODULE_ENABLED    */ | ||||||
| #define HAL_HSEM_MODULE_ENABLED | #define HAL_HSEM_MODULE_ENABLED | ||||||
| // #define HAL_I2C_MODULE_ENABLED
 | /*#define HAL_I2C_MODULE_ENABLED    */ | ||||||
| /*#define HAL_IPCC_MODULE_ENABLED   */ | /*#define HAL_IPCC_MODULE_ENABLED   */ | ||||||
| /*#define HAL_IRDA_MODULE_ENABLED   */ | /*#define HAL_IRDA_MODULE_ENABLED   */ | ||||||
| /*#define HAL_IWDG_MODULE_ENABLED   */ | /*#define HAL_IWDG_MODULE_ENABLED   */ | ||||||
| /*#define HAL_LCD_MODULE_ENABLED   */ | /*#define HAL_LCD_MODULE_ENABLED    */ | ||||||
| /*#define HAL_LPTIM_MODULE_ENABLED   */ | /*#define HAL_LPTIM_MODULE_ENABLED  */ | ||||||
| #define HAL_PCD_MODULE_ENABLED | #define HAL_PCD_MODULE_ENABLED | ||||||
| #define HAL_PKA_MODULE_ENABLED | #define HAL_PKA_MODULE_ENABLED | ||||||
| /*#define HAL_QSPI_MODULE_ENABLED   */ | /*#define HAL_QSPI_MODULE_ENABLED   */ | ||||||
| #define HAL_RNG_MODULE_ENABLED | #define HAL_RNG_MODULE_ENABLED | ||||||
| #define HAL_RTC_MODULE_ENABLED | #define HAL_RTC_MODULE_ENABLED | ||||||
| /*#define HAL_SAI_MODULE_ENABLED   */ | /*#define HAL_SAI_MODULE_ENABLED    */ | ||||||
| /*#define HAL_SMBUS_MODULE_ENABLED   */ | /*#define HAL_SMBUS_MODULE_ENABLED  */ | ||||||
| /*#define HAL_SMARTCARD_MODULE_ENABLED   */ | /*#define HAL_SMARTCARD_MODULE_ENABLED   */ | ||||||
| #define HAL_SPI_MODULE_ENABLED | /*#define HAL_SPI_MODULE_ENABLED    */ | ||||||
| #define HAL_TIM_MODULE_ENABLED | #define HAL_TIM_MODULE_ENABLED | ||||||
| /*#define HAL_TSC_MODULE_ENABLED   */ | /*#define HAL_TSC_MODULE_ENABLED    */ | ||||||
| #define HAL_UART_MODULE_ENABLED | /*#define HAL_UART_MODULE_ENABLED   */ | ||||||
| /*#define HAL_USART_MODULE_ENABLED   */ | /*#define HAL_USART_MODULE_ENABLED  */ | ||||||
| /*#define HAL_WWDG_MODULE_ENABLED   */ | /*#define HAL_WWDG_MODULE_ENABLED   */ | ||||||
| #define HAL_EXTI_MODULE_ENABLED | #define HAL_EXTI_MODULE_ENABLED | ||||||
| #define HAL_CORTEX_MODULE_ENABLED | #define HAL_CORTEX_MODULE_ENABLED | ||||||
| @ -172,7 +172,7 @@ | |||||||
|   * @brief This is the HAL system configuration section |   * @brief This is the HAL system configuration section | ||||||
|   */ |   */ | ||||||
| 
 | 
 | ||||||
| #define  VDD_VALUE				3300U                   /*!< Value of VDD in mv */ | #define  VDD_VALUE                    3300U   /*!< Value of VDD in mv */ | ||||||
| #define  TICK_INT_PRIORITY            0U      /*!< tick interrupt priority */ | #define  TICK_INT_PRIORITY            0U      /*!< tick interrupt priority */ | ||||||
| #define  USE_RTOS                     0U | #define  USE_RTOS                     0U | ||||||
| #define  PREFETCH_ENABLE              1U | #define  PREFETCH_ENABLE              1U | ||||||
|  | |||||||
| @ -1,128 +0,0 @@ | |||||||
| /**
 |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @file    adc.c |  | ||||||
|   * @brief   This file provides code for the configuration |  | ||||||
|   *          of the ADC instances. |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @attention |  | ||||||
|   * |  | ||||||
|   * <h2><center>© 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 |  | ||||||
|   * |  | ||||||
|   ****************************************************************************** |  | ||||||
|   */ |  | ||||||
| 
 |  | ||||||
| /* Includes ------------------------------------------------------------------*/ |  | ||||||
| #include "adc.h" |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN 0 */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END 0 */ |  | ||||||
| 
 |  | ||||||
| ADC_HandleTypeDef hadc1; |  | ||||||
| 
 |  | ||||||
| /* ADC1 init function */ |  | ||||||
| void MX_ADC1_Init(void) |  | ||||||
| { |  | ||||||
|   ADC_ChannelConfTypeDef sConfig = {0}; |  | ||||||
| 
 |  | ||||||
|   /** Common config
 |  | ||||||
|   */ |  | ||||||
|   hadc1.Instance = ADC1; |  | ||||||
|   hadc1.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1; |  | ||||||
|   hadc1.Init.Resolution = ADC_RESOLUTION_12B; |  | ||||||
|   hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT; |  | ||||||
|   hadc1.Init.ScanConvMode = ADC_SCAN_DISABLE; |  | ||||||
|   hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV; |  | ||||||
|   hadc1.Init.LowPowerAutoWait = DISABLE; |  | ||||||
|   hadc1.Init.ContinuousConvMode = DISABLE; |  | ||||||
|   hadc1.Init.NbrOfConversion = 1; |  | ||||||
|   hadc1.Init.DiscontinuousConvMode = DISABLE; |  | ||||||
|   hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START; |  | ||||||
|   hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; |  | ||||||
|   hadc1.Init.DMAContinuousRequests = DISABLE; |  | ||||||
|   hadc1.Init.Overrun = ADC_OVR_DATA_PRESERVED; |  | ||||||
|   hadc1.Init.OversamplingMode = DISABLE; |  | ||||||
|   if (HAL_ADC_Init(&hadc1) != HAL_OK) |  | ||||||
|   { |  | ||||||
|     Error_Handler(); |  | ||||||
|   } |  | ||||||
|   /** Configure Regular Channel
 |  | ||||||
|   */ |  | ||||||
|   sConfig.Channel = ADC_CHANNEL_14; |  | ||||||
|   sConfig.Rank = ADC_REGULAR_RANK_1; |  | ||||||
|   sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5; |  | ||||||
|   sConfig.SingleDiff = ADC_SINGLE_ENDED; |  | ||||||
|   sConfig.OffsetNumber = ADC_OFFSET_NONE; |  | ||||||
|   sConfig.Offset = 0; |  | ||||||
|   if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) |  | ||||||
|   { |  | ||||||
|     Error_Handler(); |  | ||||||
|   } |  | ||||||
| 
 |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void HAL_ADC_MspInit(ADC_HandleTypeDef* adcHandle) |  | ||||||
| { |  | ||||||
| 
 |  | ||||||
|   GPIO_InitTypeDef GPIO_InitStruct = {0}; |  | ||||||
|   if(adcHandle->Instance==ADC1) |  | ||||||
|   { |  | ||||||
|   /* USER CODE BEGIN ADC1_MspInit 0 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END ADC1_MspInit 0 */ |  | ||||||
|     /* ADC1 clock enable */ |  | ||||||
|     __HAL_RCC_ADC_CLK_ENABLE(); |  | ||||||
| 
 |  | ||||||
|     __HAL_RCC_GPIOC_CLK_ENABLE(); |  | ||||||
|     /**ADC1 GPIO Configuration
 |  | ||||||
|     PC5     ------> ADC1_IN14 |  | ||||||
|     */ |  | ||||||
|     GPIO_InitStruct.Pin = RFID_RF_IN_Pin; |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|     HAL_GPIO_Init(RFID_RF_IN_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|     /* ADC1 interrupt Init */ |  | ||||||
|     HAL_NVIC_SetPriority(ADC1_IRQn, 5, 0); |  | ||||||
|     HAL_NVIC_EnableIRQ(ADC1_IRQn); |  | ||||||
|   /* USER CODE BEGIN ADC1_MspInit 1 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END ADC1_MspInit 1 */ |  | ||||||
|   } |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void HAL_ADC_MspDeInit(ADC_HandleTypeDef* adcHandle) |  | ||||||
| { |  | ||||||
| 
 |  | ||||||
|   if(adcHandle->Instance==ADC1) |  | ||||||
|   { |  | ||||||
|   /* USER CODE BEGIN ADC1_MspDeInit 0 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END ADC1_MspDeInit 0 */ |  | ||||||
|     /* Peripheral clock disable */ |  | ||||||
|     __HAL_RCC_ADC_CLK_DISABLE(); |  | ||||||
| 
 |  | ||||||
|     /**ADC1 GPIO Configuration
 |  | ||||||
|     PC5     ------> ADC1_IN14 |  | ||||||
|     */ |  | ||||||
|     HAL_GPIO_DeInit(RFID_RF_IN_GPIO_Port, RFID_RF_IN_Pin); |  | ||||||
| 
 |  | ||||||
|     /* ADC1 interrupt Deinit */ |  | ||||||
|     HAL_NVIC_DisableIRQ(ADC1_IRQn); |  | ||||||
|   /* USER CODE BEGIN ADC1_MspDeInit 1 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END ADC1_MspDeInit 1 */ |  | ||||||
|   } |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN 1 */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END 1 */ |  | ||||||
| 
 |  | ||||||
| /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |  | ||||||
| @ -1,82 +0,0 @@ | |||||||
| /**
 |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @file    crc.c |  | ||||||
|   * @brief   This file provides code for the configuration |  | ||||||
|   *          of the CRC instances. |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @attention |  | ||||||
|   * |  | ||||||
|   * <h2><center>© 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 |  | ||||||
|   * |  | ||||||
|   ****************************************************************************** |  | ||||||
|   */ |  | ||||||
| 
 |  | ||||||
| /* Includes ------------------------------------------------------------------*/ |  | ||||||
| #include "crc.h" |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN 0 */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END 0 */ |  | ||||||
| 
 |  | ||||||
| CRC_HandleTypeDef hcrc; |  | ||||||
| 
 |  | ||||||
| /* CRC init function */ |  | ||||||
| void MX_CRC_Init(void) |  | ||||||
| { |  | ||||||
| 
 |  | ||||||
|   hcrc.Instance = CRC; |  | ||||||
|   hcrc.Init.DefaultPolynomialUse = DEFAULT_POLYNOMIAL_ENABLE; |  | ||||||
|   hcrc.Init.DefaultInitValueUse = DEFAULT_INIT_VALUE_ENABLE; |  | ||||||
|   hcrc.Init.InputDataInversionMode = CRC_INPUTDATA_INVERSION_NONE; |  | ||||||
|   hcrc.Init.OutputDataInversionMode = CRC_OUTPUTDATA_INVERSION_DISABLE; |  | ||||||
|   hcrc.InputDataFormat = CRC_INPUTDATA_FORMAT_BYTES; |  | ||||||
|   if (HAL_CRC_Init(&hcrc) != HAL_OK) |  | ||||||
|   { |  | ||||||
|     Error_Handler(); |  | ||||||
|   } |  | ||||||
| 
 |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void HAL_CRC_MspInit(CRC_HandleTypeDef* crcHandle) |  | ||||||
| { |  | ||||||
| 
 |  | ||||||
|   if(crcHandle->Instance==CRC) |  | ||||||
|   { |  | ||||||
|   /* USER CODE BEGIN CRC_MspInit 0 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END CRC_MspInit 0 */ |  | ||||||
|     /* CRC clock enable */ |  | ||||||
|     __HAL_RCC_CRC_CLK_ENABLE(); |  | ||||||
|   /* USER CODE BEGIN CRC_MspInit 1 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END CRC_MspInit 1 */ |  | ||||||
|   } |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void HAL_CRC_MspDeInit(CRC_HandleTypeDef* crcHandle) |  | ||||||
| { |  | ||||||
| 
 |  | ||||||
|   if(crcHandle->Instance==CRC) |  | ||||||
|   { |  | ||||||
|   /* USER CODE BEGIN CRC_MspDeInit 0 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END CRC_MspDeInit 0 */ |  | ||||||
|     /* Peripheral clock disable */ |  | ||||||
|     __HAL_RCC_CRC_CLK_DISABLE(); |  | ||||||
|   /* USER CODE BEGIN CRC_MspDeInit 1 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END CRC_MspDeInit 1 */ |  | ||||||
|   } |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN 1 */ |  | ||||||
| 
 |  | ||||||
| /* USER CODE END 1 */ |  | ||||||
| 
 |  | ||||||
| /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |  | ||||||
| @ -1,26 +1,18 @@ | |||||||
| #include "main.h" | #include "main.h" | ||||||
| #include "furi-hal-spi.h" | #include <furi-hal.h> | ||||||
|  | #include <furi.h> | ||||||
| 
 | 
 | ||||||
| #define SD_DUMMY_BYTE 0xFF | #define SD_DUMMY_BYTE 0xFF | ||||||
| 
 | 
 | ||||||
| const uint32_t SpiTimeout = 1000; | const uint32_t SpiTimeout = 1000; | ||||||
| uint8_t SD_IO_WriteByte(uint8_t Data); | uint8_t SD_IO_WriteByte(uint8_t Data); | ||||||
| static const FuriHalSpiDevice* sd_spi_dev = &furi_hal_spi_devices[FuriHalSpiDeviceIdSdCardFast]; |  | ||||||
| 
 | 
 | ||||||
|  | static const FuriHalSpiDevice* sd_spi_dev = &furi_hal_spi_devices[FuriHalSpiDeviceIdSdCardFast]; | ||||||
| 
 | 
 | ||||||
| /******************************************************************************
 | /******************************************************************************
 | ||||||
|                             BUS OPERATIONS |                             BUS OPERATIONS | ||||||
|  *******************************************************************************/ |  *******************************************************************************/ | ||||||
| 
 | 
 | ||||||
| /**
 |  | ||||||
|  * @brief  SPI error treatment function |  | ||||||
|  * @retval None |  | ||||||
|  */ |  | ||||||
| static void SPIx_Error(void) { |  | ||||||
|     /* Re-Initiaize the SPI communication BUS */ |  | ||||||
|     furi_hal_spi_bus_reset(sd_spi_dev->bus); |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| /**
 | /**
 | ||||||
|  * @brief  SPI Write byte(s) to device |  * @brief  SPI Write byte(s) to device | ||||||
|  * @param  DataIn: Pointer to data buffer to write |  * @param  DataIn: Pointer to data buffer to write | ||||||
| @ -29,13 +21,7 @@ static void SPIx_Error(void) { | |||||||
|  * @retval None |  * @retval None | ||||||
|  */ |  */ | ||||||
| static void SPIx_WriteReadData(const uint8_t* DataIn, uint8_t* DataOut, uint16_t DataLength) { | static void SPIx_WriteReadData(const uint8_t* DataIn, uint8_t* DataOut, uint16_t DataLength) { | ||||||
|     bool status = furi_hal_spi_bus_trx(sd_spi_dev->bus, (uint8_t*)DataIn, DataOut, DataLength, SpiTimeout); |     furi_check(furi_hal_spi_bus_trx(sd_spi_dev->bus, (uint8_t*)DataIn, DataOut, DataLength, SpiTimeout)); | ||||||
| 
 |  | ||||||
|     /* Check the communication status */ |  | ||||||
|     if(!status) { |  | ||||||
|         /* Execute user timeout callback */ |  | ||||||
|         SPIx_Error(); |  | ||||||
|     } |  | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| /**
 | /**
 | ||||||
| @ -44,15 +30,7 @@ static void SPIx_WriteReadData(const uint8_t* DataIn, uint8_t* DataOut, uint16_t | |||||||
|  * @retval None |  * @retval None | ||||||
|  */ |  */ | ||||||
| __attribute__((unused)) static void SPIx_Write(uint8_t Value) { | __attribute__((unused)) static void SPIx_Write(uint8_t Value) { | ||||||
|     uint8_t data; |     furi_check(furi_hal_spi_bus_tx(sd_spi_dev->bus, (uint8_t*)&Value, 1, SpiTimeout)); | ||||||
| 
 |  | ||||||
|     bool status = furi_hal_spi_bus_trx(sd_spi_dev->bus, (uint8_t*)&Value, &data, 1, SpiTimeout); |  | ||||||
| 
 |  | ||||||
|     /* Check the communication status */ |  | ||||||
|     if(!status) { |  | ||||||
|         /* Execute user timeout callback */ |  | ||||||
|         SPIx_Error(); |  | ||||||
|     } |  | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| /******************************************************************************
 | /******************************************************************************
 | ||||||
| @ -70,6 +48,7 @@ void SD_IO_Init(void) { | |||||||
| 
 | 
 | ||||||
|     /* SD chip select high */ |     /* SD chip select high */ | ||||||
|     hal_gpio_write(sd_spi_dev->chip_select, true); |     hal_gpio_write(sd_spi_dev->chip_select, true); | ||||||
|  |     delay_us(10); | ||||||
| 
 | 
 | ||||||
|     /* Send dummy byte 0xFF, 10 times with CS high */ |     /* Send dummy byte 0xFF, 10 times with CS high */ | ||||||
|     /* Rise CS and MOSI for 80 clocks cycles */ |     /* Rise CS and MOSI for 80 clocks cycles */ | ||||||
| @ -85,10 +64,13 @@ void SD_IO_Init(void) { | |||||||
|  * @retval None |  * @retval None | ||||||
|  */ |  */ | ||||||
| void SD_IO_CSState(uint8_t val) { | 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) { |     if(val == 1) { | ||||||
|  |         delay_us(10); // Exit guard time for some SD cards
 | ||||||
|         hal_gpio_write(sd_spi_dev->chip_select, true); |         hal_gpio_write(sd_spi_dev->chip_select, true); | ||||||
|     } else { |     } else { | ||||||
|         hal_gpio_write(sd_spi_dev->chip_select, false); |         hal_gpio_write(sd_spi_dev->chip_select, false); | ||||||
|  |         delay_us(10); // Entry guard time for some SD cards
 | ||||||
|     } |     } | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
|  | |||||||
| @ -91,8 +91,9 @@ | |||||||
| #include "stdlib.h" | #include "stdlib.h" | ||||||
| #include "string.h" | #include "string.h" | ||||||
| #include "stdio.h" | #include "stdio.h" | ||||||
| #include "spi.h" |  | ||||||
| #include <furi-hal-spi.h> | #include <furi-hal-spi.h> | ||||||
|  | #include <furi-hal-gpio.h> | ||||||
|  | #include <furi-hal-resources.h> | ||||||
| #include <furi-hal-power.h> | #include <furi-hal-power.h> | ||||||
| #include <furi-hal-delay.h> | #include <furi-hal-delay.h> | ||||||
| #include <furi-hal-sd.h> | #include <furi-hal-sd.h> | ||||||
| @ -282,6 +283,25 @@ static uint8_t SD_ReadData(void); | |||||||
| 
 | 
 | ||||||
| /* Private functions ---------------------------------------------------------*/ | /* Private functions ---------------------------------------------------------*/ | ||||||
| 
 | 
 | ||||||
|  | void SD_SPI_Bus_To_Down_State(){ | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_d_miso, GpioModeOutputPushPull, GpioPullNo, GpioSpeedVeryHigh, GpioAltFnUnused); | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_d_mosi, GpioModeOutputPushPull, GpioPullNo, GpioSpeedVeryHigh, GpioAltFnUnused); | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_d_sck, GpioModeOutputPushPull, GpioPullNo, GpioSpeedVeryHigh, GpioAltFnUnused); | ||||||
|  | 
 | ||||||
|  |     hal_gpio_write(&gpio_sdcard_cs, false); | ||||||
|  |     hal_gpio_write(&gpio_spi_d_miso, false); | ||||||
|  |     hal_gpio_write(&gpio_spi_d_mosi, false); | ||||||
|  |     hal_gpio_write(&gpio_spi_d_sck, false); | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void SD_SPI_Bus_To_Normal_State(){ | ||||||
|  |     hal_gpio_write(&gpio_sdcard_cs, true); | ||||||
|  | 
 | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_d_miso, GpioModeAltFunctionPushPull, GpioPullUp, GpioSpeedVeryHigh, GpioAltFn5SPI2); | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_d_mosi, GpioModeAltFunctionPushPull, GpioPullUp, GpioSpeedVeryHigh, GpioAltFn5SPI2); | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_d_sck, GpioModeAltFunctionPushPull, GpioPullUp, GpioSpeedVeryHigh, GpioAltFn5SPI2); | ||||||
|  | } | ||||||
|  | 
 | ||||||
| /** @defgroup STM32_ADAFRUIT_SD_Private_Functions
 | /** @defgroup STM32_ADAFRUIT_SD_Private_Functions
 | ||||||
|   * @{ |   * @{ | ||||||
|   */ |   */ | ||||||
| @ -295,9 +315,7 @@ static uint8_t SD_ReadData(void); | |||||||
|   */ |   */ | ||||||
| uint8_t BSP_SD_Init(bool reset_card) { | uint8_t BSP_SD_Init(bool reset_card) { | ||||||
|     /* Slow speed init */ |     /* Slow speed init */ | ||||||
|     const FuriHalSpiDevice* sd_spi_slow_dev = &furi_hal_spi_devices[FuriHalSpiDeviceIdSdCardSlow]; |     const FuriHalSpiDevice* sd_spi_slow_dev = furi_hal_spi_device_get(FuriHalSpiDeviceIdSdCardSlow); | ||||||
|     furi_hal_spi_bus_lock(sd_spi_slow_dev->bus); |  | ||||||
|     furi_hal_spi_bus_configure(sd_spi_slow_dev->bus, sd_spi_slow_dev->config); |  | ||||||
| 
 | 
 | ||||||
|     /* We must reset card in spi_lock context */ |     /* We must reset card in spi_lock context */ | ||||||
|     if(reset_card) { |     if(reset_card) { | ||||||
| @ -326,7 +344,7 @@ uint8_t BSP_SD_Init(bool reset_card) { | |||||||
|         if(res == BSP_SD_OK) break; |         if(res == BSP_SD_OK) break; | ||||||
|     } |     } | ||||||
| 
 | 
 | ||||||
|     furi_hal_spi_bus_unlock(sd_spi_slow_dev->bus); |     furi_hal_spi_device_return(sd_spi_slow_dev); | ||||||
| 
 | 
 | ||||||
|     /* SD initialized and set to SPI mode properly */ |     /* SD initialized and set to SPI mode properly */ | ||||||
|     return res; |     return res; | ||||||
|  | |||||||
| @ -35,7 +35,6 @@ | |||||||
| 
 | 
 | ||||||
| /* Includes ------------------------------------------------------------------*/ | /* Includes ------------------------------------------------------------------*/ | ||||||
| #include "user_diskio.h" | #include "user_diskio.h" | ||||||
| #include "spi.h" |  | ||||||
| #include "furi-hal-spi.h" | #include "furi-hal-spi.h" | ||||||
| /* Private typedef -----------------------------------------------------------*/ | /* Private typedef -----------------------------------------------------------*/ | ||||||
| /* Private define ------------------------------------------------------------*/ | /* Private define ------------------------------------------------------------*/ | ||||||
| @ -53,7 +52,6 @@ static DSTATUS User_CheckStatus(BYTE lun) { | |||||||
|     return Stat; |     return Stat; | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| static const FuriHalSpiDevice* sd_spi_fast_dev = &furi_hal_spi_devices[FuriHalSpiDeviceIdSdCardFast]; |  | ||||||
| /* USER CODE END DECL */ | /* USER CODE END DECL */ | ||||||
| 
 | 
 | ||||||
| /* Private function prototypes -----------------------------------------------*/ | /* Private function prototypes -----------------------------------------------*/ | ||||||
| @ -89,12 +87,11 @@ Diskio_drvTypeDef USER_Driver = { | |||||||
| DSTATUS USER_initialize(BYTE pdrv) { | DSTATUS USER_initialize(BYTE pdrv) { | ||||||
|     /* USER CODE BEGIN INIT */ |     /* USER CODE BEGIN INIT */ | ||||||
| 
 | 
 | ||||||
|     furi_hal_spi_bus_lock(sd_spi_fast_dev->bus); |     const FuriHalSpiDevice* sd_spi_fast_dev = furi_hal_spi_device_get(FuriHalSpiDeviceIdSdCardFast); | ||||||
|     furi_hal_spi_bus_configure(sd_spi_fast_dev->bus, sd_spi_fast_dev->config); |  | ||||||
| 
 | 
 | ||||||
|     DSTATUS status = User_CheckStatus(pdrv); |     DSTATUS status = User_CheckStatus(pdrv); | ||||||
| 
 | 
 | ||||||
|     furi_hal_spi_bus_unlock(sd_spi_fast_dev->bus); |     furi_hal_spi_device_return(sd_spi_fast_dev); | ||||||
| 
 | 
 | ||||||
|     return status; |     return status; | ||||||
|     /* USER CODE END INIT */ |     /* USER CODE END INIT */ | ||||||
| @ -123,8 +120,7 @@ DRESULT USER_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count) { | |||||||
|     /* USER CODE BEGIN READ */ |     /* USER CODE BEGIN READ */ | ||||||
|     DRESULT res = RES_ERROR; |     DRESULT res = RES_ERROR; | ||||||
| 
 | 
 | ||||||
|     furi_hal_spi_bus_lock(sd_spi_fast_dev->bus); |     const FuriHalSpiDevice* sd_spi_fast_dev = furi_hal_spi_device_get(FuriHalSpiDeviceIdSdCardFast); | ||||||
|     furi_hal_spi_bus_configure(sd_spi_fast_dev->bus, sd_spi_fast_dev->config); |  | ||||||
| 
 | 
 | ||||||
|     if(BSP_SD_ReadBlocks((uint32_t*)buff, (uint32_t)(sector), count, SD_DATATIMEOUT) == MSD_OK) { |     if(BSP_SD_ReadBlocks((uint32_t*)buff, (uint32_t)(sector), count, SD_DATATIMEOUT) == MSD_OK) { | ||||||
|         /* wait until the read operation is finished */ |         /* wait until the read operation is finished */ | ||||||
| @ -133,7 +129,7 @@ DRESULT USER_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count) { | |||||||
|         res = RES_OK; |         res = RES_OK; | ||||||
|     } |     } | ||||||
| 
 | 
 | ||||||
|     furi_hal_spi_bus_unlock(sd_spi_fast_dev->bus); |     furi_hal_spi_device_return(sd_spi_fast_dev); | ||||||
| 
 | 
 | ||||||
|     return res; |     return res; | ||||||
|     /* USER CODE END READ */ |     /* USER CODE END READ */ | ||||||
| @ -153,8 +149,7 @@ DRESULT USER_write(BYTE pdrv, const BYTE* buff, DWORD sector, UINT count) { | |||||||
|     /* USER CODE HERE */ |     /* USER CODE HERE */ | ||||||
|     DRESULT res = RES_ERROR; |     DRESULT res = RES_ERROR; | ||||||
| 
 | 
 | ||||||
|     furi_hal_spi_bus_lock(sd_spi_fast_dev->bus); |     const FuriHalSpiDevice* sd_spi_fast_dev = furi_hal_spi_device_get(FuriHalSpiDeviceIdSdCardFast); | ||||||
|     furi_hal_spi_bus_configure(sd_spi_fast_dev->bus, sd_spi_fast_dev->config); |  | ||||||
| 
 | 
 | ||||||
|     if(BSP_SD_WriteBlocks((uint32_t*)buff, (uint32_t)(sector), count, SD_DATATIMEOUT) == MSD_OK) { |     if(BSP_SD_WriteBlocks((uint32_t*)buff, (uint32_t)(sector), count, SD_DATATIMEOUT) == MSD_OK) { | ||||||
|         /* wait until the Write operation is finished */ |         /* wait until the Write operation is finished */ | ||||||
| @ -163,7 +158,7 @@ DRESULT USER_write(BYTE pdrv, const BYTE* buff, DWORD sector, UINT count) { | |||||||
|         res = RES_OK; |         res = RES_OK; | ||||||
|     } |     } | ||||||
| 
 | 
 | ||||||
|     furi_hal_spi_bus_unlock(sd_spi_fast_dev->bus); |     furi_hal_spi_device_return(sd_spi_fast_dev); | ||||||
| 
 | 
 | ||||||
|     return res; |     return res; | ||||||
|     /* USER CODE END WRITE */ |     /* USER CODE END WRITE */ | ||||||
| @ -185,8 +180,7 @@ DRESULT USER_ioctl(BYTE pdrv, BYTE cmd, void* buff) { | |||||||
| 
 | 
 | ||||||
|     if(Stat & STA_NOINIT) return RES_NOTRDY; |     if(Stat & STA_NOINIT) return RES_NOTRDY; | ||||||
| 
 | 
 | ||||||
|     furi_hal_spi_bus_lock(sd_spi_fast_dev->bus); |     const FuriHalSpiDevice* sd_spi_fast_dev = furi_hal_spi_device_get(FuriHalSpiDeviceIdSdCardFast); | ||||||
|     furi_hal_spi_bus_configure(sd_spi_fast_dev->bus, sd_spi_fast_dev->config); |  | ||||||
| 
 | 
 | ||||||
|     switch(cmd) { |     switch(cmd) { | ||||||
|     /* Make sure that no pending write process */ |     /* Make sure that no pending write process */ | ||||||
| @ -219,7 +213,7 @@ DRESULT USER_ioctl(BYTE pdrv, BYTE cmd, void* buff) { | |||||||
|         res = RES_PARERR; |         res = RES_PARERR; | ||||||
|     } |     } | ||||||
| 
 | 
 | ||||||
|     furi_hal_spi_bus_unlock(sd_spi_fast_dev->bus); |     furi_hal_spi_device_return(sd_spi_fast_dev); | ||||||
| 
 | 
 | ||||||
|     return res; |     return res; | ||||||
|     /* USER CODE END IOCTL */ |     /* USER CODE END IOCTL */ | ||||||
|  | |||||||
| @ -67,12 +67,6 @@ void MX_GPIO_Init(void) { | |||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |     GPIO_InitStruct.Pull = GPIO_NOPULL; | ||||||
|     HAL_GPIO_Init(RFID_PULL_GPIO_Port, &GPIO_InitStruct); |     HAL_GPIO_Init(RFID_PULL_GPIO_Port, &GPIO_InitStruct); | ||||||
| 
 | 
 | ||||||
|     /*Configure GPIO pin : PtPin */ |  | ||||||
|     GPIO_InitStruct.Pin = CC1101_G0_Pin; |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING_FALLING; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_PULLDOWN; |  | ||||||
|     // HAL_GPIO_Init(CC1101_G0_GPIO_Port, &GPIO_InitStruct);
 |  | ||||||
| 
 |  | ||||||
|     /*Configure GPIO pins : PBPin PBPin PBPin */ |     /*Configure GPIO pins : PBPin PBPin PBPin */ | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; |     GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |     GPIO_InitStruct.Pull = GPIO_NOPULL; | ||||||
| @ -107,22 +101,6 @@ void MX_GPIO_Init(void) { | |||||||
|     GPIO_InitStruct.Pin = DISPLAY_RST_Pin; |     GPIO_InitStruct.Pin = DISPLAY_RST_Pin; | ||||||
|     HAL_GPIO_Init(DISPLAY_RST_GPIO_Port, &GPIO_InitStruct); |     HAL_GPIO_Init(DISPLAY_RST_GPIO_Port, &GPIO_InitStruct); | ||||||
| 
 | 
 | ||||||
|     /* NFC_CS */ |  | ||||||
|     HAL_GPIO_WritePin(NFC_CS_GPIO_Port, NFC_CS_Pin, GPIO_PIN_SET); |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|     GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; |  | ||||||
|     GPIO_InitStruct.Pin = NFC_CS_Pin; |  | ||||||
|     HAL_GPIO_Init(NFC_CS_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|     /* DISPLAY_CS */ |  | ||||||
|     HAL_GPIO_WritePin(DISPLAY_CS_GPIO_Port, DISPLAY_CS_Pin, GPIO_PIN_SET); |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|     GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; |  | ||||||
|     GPIO_InitStruct.Pin = DISPLAY_CS_Pin; |  | ||||||
|     HAL_GPIO_Init(DISPLAY_CS_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|     /* DISPLAY_DI */ |     /* DISPLAY_DI */ | ||||||
|     HAL_GPIO_WritePin(DISPLAY_DI_GPIO_Port, DISPLAY_DI_Pin, GPIO_PIN_RESET); |     HAL_GPIO_WritePin(DISPLAY_DI_GPIO_Port, DISPLAY_DI_Pin, GPIO_PIN_RESET); | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; |     GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; | ||||||
| @ -137,21 +115,6 @@ void MX_GPIO_Init(void) { | |||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |     GPIO_InitStruct.Pull = GPIO_NOPULL; | ||||||
|     HAL_GPIO_Init(SD_CD_GPIO_Port, &GPIO_InitStruct); |     HAL_GPIO_Init(SD_CD_GPIO_Port, &GPIO_InitStruct); | ||||||
| 
 | 
 | ||||||
|     /* SD_CS */ |  | ||||||
|     GPIO_InitStruct.Pin = SD_CS_Pin; |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|     GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; |  | ||||||
|     HAL_GPIO_Init(SD_CS_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|     /* CC1101_CS */ |  | ||||||
|     HAL_GPIO_WritePin(CC1101_CS_GPIO_Port, CC1101_CS_Pin, GPIO_PIN_SET); |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|     GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; |  | ||||||
|     GPIO_InitStruct.Pin = CC1101_CS_Pin; |  | ||||||
|     HAL_GPIO_Init(CC1101_CS_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|     /* Enable all NVIC lines related to gpio */ |     /* Enable all NVIC lines related to gpio */ | ||||||
|     HAL_NVIC_SetPriority(EXTI0_IRQn, 5, 0); |     HAL_NVIC_SetPriority(EXTI0_IRQn, 5, 0); | ||||||
|     HAL_NVIC_EnableIRQ(EXTI0_IRQn); |     HAL_NVIC_EnableIRQ(EXTI0_IRQn); | ||||||
|  | |||||||
| @ -1,374 +0,0 @@ | |||||||
| /**
 |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @file    spi.c |  | ||||||
|   * @brief   This file provides code for the configuration |  | ||||||
|   *          of the SPI instances. |  | ||||||
|   ****************************************************************************** |  | ||||||
|   * @attention |  | ||||||
|   * |  | ||||||
|   * <h2><center>© 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 |  | ||||||
|   * |  | ||||||
|   ****************************************************************************** |  | ||||||
|   */ |  | ||||||
| 
 |  | ||||||
| /* Includes ------------------------------------------------------------------*/ |  | ||||||
| #include "spi.h" |  | ||||||
| #include <cmsis_os2.h> |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN 0 */ |  | ||||||
| void Enable_SPI(SPI_HandleTypeDef* spi); |  | ||||||
| /* USER CODE END 0 */ |  | ||||||
| 
 |  | ||||||
| SPI_HandleTypeDef hspi1; |  | ||||||
| SPI_HandleTypeDef hspi2; |  | ||||||
| 
 |  | ||||||
| /* SPI1 init function */ |  | ||||||
| void MX_SPI1_Init(void) |  | ||||||
| { |  | ||||||
| 
 |  | ||||||
|   hspi1.Instance = SPI1; |  | ||||||
|   hspi1.Init.Mode = SPI_MODE_MASTER; |  | ||||||
|   hspi1.Init.Direction = SPI_DIRECTION_2LINES; |  | ||||||
|   hspi1.Init.DataSize = SPI_DATASIZE_8BIT; |  | ||||||
|   hspi1.Init.CLKPolarity = SPI_POLARITY_LOW; |  | ||||||
|   hspi1.Init.CLKPhase = SPI_PHASE_2EDGE; |  | ||||||
|   hspi1.Init.NSS = SPI_NSS_SOFT; |  | ||||||
|   hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16; |  | ||||||
|   hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB; |  | ||||||
|   hspi1.Init.TIMode = SPI_TIMODE_DISABLE; |  | ||||||
|   hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; |  | ||||||
|   hspi1.Init.CRCPolynomial = 7; |  | ||||||
|   hspi1.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE; |  | ||||||
|   hspi1.Init.NSSPMode = SPI_NSS_PULSE_DISABLE; |  | ||||||
|   if (HAL_SPI_Init(&hspi1) != HAL_OK) |  | ||||||
|   { |  | ||||||
|     Error_Handler(); |  | ||||||
|   } |  | ||||||
| 
 |  | ||||||
| } |  | ||||||
| /* SPI2 init function */ |  | ||||||
| void MX_SPI2_Init(void) |  | ||||||
| { |  | ||||||
| 
 |  | ||||||
|   hspi2.Instance = SPI2; |  | ||||||
|   hspi2.Init.Mode = SPI_MODE_MASTER; |  | ||||||
|   hspi2.Init.Direction = SPI_DIRECTION_2LINES; |  | ||||||
|   hspi2.Init.DataSize = SPI_DATASIZE_8BIT; |  | ||||||
|   hspi2.Init.CLKPolarity = SPI_POLARITY_LOW; |  | ||||||
|   hspi2.Init.CLKPhase = SPI_PHASE_1EDGE; |  | ||||||
|   hspi2.Init.NSS = SPI_NSS_SOFT; |  | ||||||
|   hspi2.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16; |  | ||||||
|   hspi2.Init.FirstBit = SPI_FIRSTBIT_MSB; |  | ||||||
|   hspi2.Init.TIMode = SPI_TIMODE_DISABLE; |  | ||||||
|   hspi2.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; |  | ||||||
|   hspi2.Init.CRCPolynomial = 7; |  | ||||||
|   hspi2.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE; |  | ||||||
|   hspi2.Init.NSSPMode = SPI_NSS_PULSE_ENABLE; |  | ||||||
|   if (HAL_SPI_Init(&hspi2) != HAL_OK) |  | ||||||
|   { |  | ||||||
|     Error_Handler(); |  | ||||||
|   } |  | ||||||
| 
 |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle) |  | ||||||
| { |  | ||||||
| 
 |  | ||||||
|   GPIO_InitTypeDef GPIO_InitStruct = {0}; |  | ||||||
|   if(spiHandle->Instance==SPI1) |  | ||||||
|   { |  | ||||||
|   /* USER CODE BEGIN SPI1_MspInit 0 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END SPI1_MspInit 0 */ |  | ||||||
|     /* SPI1 clock enable */ |  | ||||||
|     __HAL_RCC_SPI1_CLK_ENABLE(); |  | ||||||
| 
 |  | ||||||
|     __HAL_RCC_GPIOA_CLK_ENABLE(); |  | ||||||
|     __HAL_RCC_GPIOB_CLK_ENABLE(); |  | ||||||
|     /**SPI1 GPIO Configuration
 |  | ||||||
|     PA5     ------> SPI1_SCK |  | ||||||
|     PB4     ------> SPI1_MISO |  | ||||||
|     PB5     ------> SPI1_MOSI |  | ||||||
|     */ |  | ||||||
|     GPIO_InitStruct.Pin = SPI_R_SCK_Pin; |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|     GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; |  | ||||||
|     GPIO_InitStruct.Alternate = GPIO_AF5_SPI1; |  | ||||||
|     HAL_GPIO_Init(SPI_R_SCK_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|     GPIO_InitStruct.Pin = SPI_R_MISO_Pin|SPI_R_MOSI_Pin; |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|     GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; |  | ||||||
|     GPIO_InitStruct.Alternate = GPIO_AF5_SPI1; |  | ||||||
|     HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|   /* USER CODE BEGIN SPI1_MspInit 1 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END SPI1_MspInit 1 */ |  | ||||||
|   } |  | ||||||
|   else if(spiHandle->Instance==SPI2) |  | ||||||
|   { |  | ||||||
|   /* USER CODE BEGIN SPI2_MspInit 0 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END SPI2_MspInit 0 */ |  | ||||||
|     /* SPI2 clock enable */ |  | ||||||
|     __HAL_RCC_SPI2_CLK_ENABLE(); |  | ||||||
| 
 |  | ||||||
|     __HAL_RCC_GPIOC_CLK_ENABLE(); |  | ||||||
|     __HAL_RCC_GPIOB_CLK_ENABLE(); |  | ||||||
|     __HAL_RCC_GPIOD_CLK_ENABLE(); |  | ||||||
|     /**SPI2 GPIO Configuration
 |  | ||||||
|     PC2     ------> SPI2_MISO |  | ||||||
|     PB15     ------> SPI2_MOSI |  | ||||||
|     PD1     ------> SPI2_SCK |  | ||||||
|     */ |  | ||||||
|     GPIO_InitStruct.Pin = GPIO_PIN_2; |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|     GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; |  | ||||||
|     GPIO_InitStruct.Alternate = GPIO_AF5_SPI2; |  | ||||||
|     HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|     GPIO_InitStruct.Pin = SPI_D_MOSI_Pin; |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|     GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; |  | ||||||
|     GPIO_InitStruct.Alternate = GPIO_AF5_SPI2; |  | ||||||
|     HAL_GPIO_Init(SPI_D_MOSI_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|     GPIO_InitStruct.Pin = SPI_D_SCK_Pin; |  | ||||||
|     GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; |  | ||||||
|     GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|     GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; |  | ||||||
|     GPIO_InitStruct.Alternate = GPIO_AF5_SPI2; |  | ||||||
|     HAL_GPIO_Init(SPI_D_SCK_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|   /* USER CODE BEGIN SPI2_MspInit 1 */ |  | ||||||
|    |  | ||||||
|   // SD Card need faster spi gpio
 |  | ||||||
|   GPIO_InitStruct.Pin = GPIO_PIN_2; |  | ||||||
|   GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; |  | ||||||
|   GPIO_InitStruct.Pull = GPIO_PULLUP; |  | ||||||
|   GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; |  | ||||||
|   GPIO_InitStruct.Alternate = GPIO_AF5_SPI2; |  | ||||||
|   HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|   GPIO_InitStruct.Pin = SPI_D_MOSI_Pin; |  | ||||||
|   GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; |  | ||||||
|   GPIO_InitStruct.Pull = GPIO_PULLUP; |  | ||||||
|   GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; |  | ||||||
|   GPIO_InitStruct.Alternate = GPIO_AF5_SPI2; |  | ||||||
|   HAL_GPIO_Init(SPI_D_MOSI_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|   GPIO_InitStruct.Pin = SPI_D_SCK_Pin; |  | ||||||
|   GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; |  | ||||||
|   GPIO_InitStruct.Pull = GPIO_PULLUP; |  | ||||||
|   GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; |  | ||||||
|   GPIO_InitStruct.Alternate = GPIO_AF5_SPI2; |  | ||||||
|   HAL_GPIO_Init(SPI_D_SCK_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END SPI2_MspInit 1 */ |  | ||||||
|   } |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void HAL_SPI_MspDeInit(SPI_HandleTypeDef* spiHandle) |  | ||||||
| { |  | ||||||
| 
 |  | ||||||
|   if(spiHandle->Instance==SPI1) |  | ||||||
|   { |  | ||||||
|   /* USER CODE BEGIN SPI1_MspDeInit 0 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END SPI1_MspDeInit 0 */ |  | ||||||
|     /* Peripheral clock disable */ |  | ||||||
|     __HAL_RCC_SPI1_CLK_DISABLE(); |  | ||||||
| 
 |  | ||||||
|     /**SPI1 GPIO Configuration
 |  | ||||||
|     PA5     ------> SPI1_SCK |  | ||||||
|     PB4     ------> SPI1_MISO |  | ||||||
|     PB5     ------> SPI1_MOSI |  | ||||||
|     */ |  | ||||||
|     HAL_GPIO_DeInit(SPI_R_SCK_GPIO_Port, SPI_R_SCK_Pin); |  | ||||||
| 
 |  | ||||||
|     HAL_GPIO_DeInit(GPIOB, SPI_R_MISO_Pin|SPI_R_MOSI_Pin); |  | ||||||
| 
 |  | ||||||
|   /* USER CODE BEGIN SPI1_MspDeInit 1 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END SPI1_MspDeInit 1 */ |  | ||||||
|   } |  | ||||||
|   else if(spiHandle->Instance==SPI2) |  | ||||||
|   { |  | ||||||
|   /* USER CODE BEGIN SPI2_MspDeInit 0 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END SPI2_MspDeInit 0 */ |  | ||||||
|     /* Peripheral clock disable */ |  | ||||||
|     __HAL_RCC_SPI2_CLK_DISABLE(); |  | ||||||
| 
 |  | ||||||
|     /**SPI2 GPIO Configuration
 |  | ||||||
|     PC2     ------> SPI2_MISO |  | ||||||
|     PB15     ------> SPI2_MOSI |  | ||||||
|     PD1     ------> SPI2_SCK |  | ||||||
|     */ |  | ||||||
|     HAL_GPIO_DeInit(GPIOC, GPIO_PIN_2); |  | ||||||
| 
 |  | ||||||
|     HAL_GPIO_DeInit(SPI_D_MOSI_GPIO_Port, SPI_D_MOSI_Pin); |  | ||||||
| 
 |  | ||||||
|     HAL_GPIO_DeInit(SPI_D_SCK_GPIO_Port, SPI_D_SCK_Pin); |  | ||||||
| 
 |  | ||||||
|   /* USER CODE BEGIN SPI2_MspDeInit 1 */ |  | ||||||
| 
 |  | ||||||
|   /* USER CODE END SPI2_MspDeInit 1 */ |  | ||||||
|   } |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| /* USER CODE BEGIN 1 */ |  | ||||||
| 
 |  | ||||||
| void NFC_SPI_Reconfigure() { |  | ||||||
|   osKernelLock(); |  | ||||||
| 
 |  | ||||||
|   SPI_R.Init.Mode = SPI_MODE_MASTER; |  | ||||||
|   SPI_R.Init.Direction = SPI_DIRECTION_2LINES; |  | ||||||
|   SPI_R.Init.DataSize = SPI_DATASIZE_8BIT; |  | ||||||
|   SPI_R.Init.CLKPolarity = SPI_POLARITY_LOW; |  | ||||||
|   SPI_R.Init.CLKPhase = SPI_PHASE_2EDGE; |  | ||||||
|   SPI_R.Init.NSS = SPI_NSS_SOFT; |  | ||||||
|   SPI_R.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8; // 8mhz, 10mhz is max
 |  | ||||||
|   SPI_R.Init.FirstBit = SPI_FIRSTBIT_MSB; |  | ||||||
|   SPI_R.Init.TIMode = SPI_TIMODE_DISABLE; |  | ||||||
|   SPI_R.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; |  | ||||||
|   SPI_R.Init.CRCPolynomial = 7; |  | ||||||
|   SPI_R.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE; |  | ||||||
|   SPI_R.Init.NSSPMode = SPI_NSS_PULSE_DISABLE; |  | ||||||
| 
 |  | ||||||
|   if (HAL_SPI_Init(&SPI_R) != HAL_OK) { |  | ||||||
|       Error_Handler(); |  | ||||||
|   } |  | ||||||
| 
 |  | ||||||
|   Enable_SPI(&SPI_R); |  | ||||||
| 
 |  | ||||||
|   osKernelUnlock(); |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void SD_SPI_Reconfigure_Slow(void) { |  | ||||||
|   osKernelLock(); |  | ||||||
| 
 |  | ||||||
|   SPI_SD_HANDLE.Init.Mode = SPI_MODE_MASTER; |  | ||||||
|   SPI_SD_HANDLE.Init.Direction = SPI_DIRECTION_2LINES; |  | ||||||
|   SPI_SD_HANDLE.Init.DataSize = SPI_DATASIZE_8BIT; |  | ||||||
|   SPI_SD_HANDLE.Init.CLKPolarity = SPI_POLARITY_LOW; |  | ||||||
|   SPI_SD_HANDLE.Init.CLKPhase = SPI_PHASE_1EDGE; |  | ||||||
|   SPI_SD_HANDLE.Init.NSS = SPI_NSS_SOFT; |  | ||||||
|   SPI_SD_HANDLE.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256; |  | ||||||
|   SPI_SD_HANDLE.Init.FirstBit = SPI_FIRSTBIT_MSB; |  | ||||||
|   SPI_SD_HANDLE.Init.TIMode = SPI_TIMODE_DISABLE; |  | ||||||
|   SPI_SD_HANDLE.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; |  | ||||||
|   SPI_SD_HANDLE.Init.CRCPolynomial = 7; |  | ||||||
|   SPI_SD_HANDLE.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE; |  | ||||||
|   SPI_SD_HANDLE.Init.NSSPMode = SPI_NSS_PULSE_ENABLE; |  | ||||||
| 
 |  | ||||||
|   if(HAL_SPI_Init(&SPI_SD_HANDLE) != HAL_OK) { |  | ||||||
|       Error_Handler(); |  | ||||||
|   } |  | ||||||
| 
 |  | ||||||
|   Enable_SPI(&SPI_SD_HANDLE); |  | ||||||
| 
 |  | ||||||
|   osKernelUnlock(); |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void SD_SPI_Reconfigure_Fast(void) { |  | ||||||
|   osKernelLock(); |  | ||||||
| 
 |  | ||||||
|   SPI_SD_HANDLE.Init.Mode = SPI_MODE_MASTER; |  | ||||||
|   SPI_SD_HANDLE.Init.Direction = SPI_DIRECTION_2LINES; |  | ||||||
|   SPI_SD_HANDLE.Init.DataSize = SPI_DATASIZE_8BIT; |  | ||||||
|   SPI_SD_HANDLE.Init.CLKPolarity = SPI_POLARITY_LOW; |  | ||||||
|   SPI_SD_HANDLE.Init.CLKPhase = SPI_PHASE_1EDGE; |  | ||||||
|   SPI_SD_HANDLE.Init.NSS = SPI_NSS_SOFT; |  | ||||||
|   SPI_SD_HANDLE.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; |  | ||||||
|   SPI_SD_HANDLE.Init.FirstBit = SPI_FIRSTBIT_MSB; |  | ||||||
|   SPI_SD_HANDLE.Init.TIMode = SPI_TIMODE_DISABLE; |  | ||||||
|   SPI_SD_HANDLE.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; |  | ||||||
|   SPI_SD_HANDLE.Init.CRCPolynomial = 7; |  | ||||||
|   SPI_SD_HANDLE.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE; |  | ||||||
|   SPI_SD_HANDLE.Init.NSSPMode = SPI_NSS_PULSE_ENABLE; |  | ||||||
| 
 |  | ||||||
|   if(HAL_SPI_Init(&SPI_SD_HANDLE) != HAL_OK) { |  | ||||||
|       Error_Handler(); |  | ||||||
|   } |  | ||||||
| 
 |  | ||||||
|   Enable_SPI(&SPI_SD_HANDLE); |  | ||||||
| 
 |  | ||||||
|   osKernelUnlock(); |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void CC1101_SPI_Reconfigure(void) { |  | ||||||
|   osKernelLock(); |  | ||||||
| 
 |  | ||||||
|   SPI_R.Init.Mode = SPI_MODE_MASTER; |  | ||||||
|   SPI_R.Init.Direction = SPI_DIRECTION_2LINES; |  | ||||||
|   SPI_R.Init.DataSize = SPI_DATASIZE_8BIT; |  | ||||||
|   SPI_R.Init.CLKPolarity = SPI_POLARITY_LOW; |  | ||||||
|   SPI_R.Init.CLKPhase = SPI_PHASE_1EDGE; |  | ||||||
|   SPI_R.Init.NSS = SPI_NSS_SOFT; |  | ||||||
|   SPI_R.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_64; |  | ||||||
|   SPI_R.Init.FirstBit = SPI_FIRSTBIT_MSB; |  | ||||||
|   SPI_R.Init.TIMode = SPI_TIMODE_DISABLE; |  | ||||||
|   SPI_R.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; |  | ||||||
|   SPI_R.Init.CRCPolynomial = 7; |  | ||||||
|   SPI_R.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE; |  | ||||||
|   SPI_R.Init.NSSPMode = SPI_NSS_PULSE_DISABLE; |  | ||||||
| 
 |  | ||||||
|   if(HAL_SPI_Init(&SPI_R) != HAL_OK) { |  | ||||||
|       Error_Handler(); |  | ||||||
|   } |  | ||||||
| 
 |  | ||||||
|   Enable_SPI(&SPI_R); |  | ||||||
| 
 |  | ||||||
|   osKernelUnlock(); |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void Enable_SPI(SPI_HandleTypeDef* spi_instance){ |  | ||||||
|   if((spi_instance->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) { |  | ||||||
|     __HAL_SPI_ENABLE(spi_instance); |  | ||||||
|   } |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void SD_SPI_Bus_To_Down_State(){ |  | ||||||
|   GPIO_InitTypeDef GPIO_InitStruct = {0}; |  | ||||||
|   GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; |  | ||||||
| 
 |  | ||||||
|   GPIO_InitStruct.Pin = GPIO_PIN_2; |  | ||||||
|   GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; |  | ||||||
|   GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|   HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|   GPIO_InitStruct.Pin = SPI_D_MOSI_Pin; |  | ||||||
|   GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; |  | ||||||
|   GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|   HAL_GPIO_Init(SPI_D_MOSI_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|   GPIO_InitStruct.Pin = SPI_D_SCK_Pin; |  | ||||||
|   GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; |  | ||||||
|   GPIO_InitStruct.Pull = GPIO_NOPULL; |  | ||||||
|   HAL_GPIO_Init(SPI_D_SCK_GPIO_Port, &GPIO_InitStruct); |  | ||||||
| 
 |  | ||||||
|   HAL_GPIO_WritePin(SD_CS_GPIO_Port, SD_CS_Pin, GPIO_PIN_RESET); |  | ||||||
|   HAL_GPIO_WritePin(GPIOC, GPIO_PIN_2, GPIO_PIN_RESET); |  | ||||||
|   HAL_GPIO_WritePin(SPI_D_MOSI_GPIO_Port, SPI_D_MOSI_Pin, GPIO_PIN_RESET); |  | ||||||
|   HAL_GPIO_WritePin(SPI_D_SCK_GPIO_Port, SPI_D_SCK_Pin, GPIO_PIN_RESET); |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void SD_SPI_Bus_To_Normal_State(){ |  | ||||||
|   HAL_GPIO_WritePin(SD_CS_GPIO_Port, SD_CS_Pin, GPIO_PIN_SET); |  | ||||||
|   HAL_SPI_MspInit(&SPI_SD_HANDLE); |  | ||||||
| } |  | ||||||
| /* USER CODE END 1 */ |  | ||||||
| 
 |  | ||||||
| /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |  | ||||||
| @ -4,7 +4,6 @@ | |||||||
| #include "task.h" | #include "task.h" | ||||||
| 
 | 
 | ||||||
| extern PCD_HandleTypeDef hpcd_USB_FS; | extern PCD_HandleTypeDef hpcd_USB_FS; | ||||||
| extern ADC_HandleTypeDef hadc1; |  | ||||||
| extern COMP_HandleTypeDef hcomp1; | extern COMP_HandleTypeDef hcomp1; | ||||||
| extern RTC_HandleTypeDef hrtc; | extern RTC_HandleTypeDef hrtc; | ||||||
| extern TIM_HandleTypeDef htim1; | extern TIM_HandleTypeDef htim1; | ||||||
| @ -20,10 +19,6 @@ void SysTick_Handler(void) { | |||||||
|     HAL_IncTick(); |     HAL_IncTick(); | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void ADC1_IRQHandler(void) { |  | ||||||
|     HAL_ADC_IRQHandler(&hadc1); |  | ||||||
| } |  | ||||||
| 
 |  | ||||||
| void USB_LP_IRQHandler(void) { | void USB_LP_IRQHandler(void) { | ||||||
|     HAL_PCD_IRQHandler(&hpcd_USB_FS); |     HAL_PCD_IRQHandler(&hpcd_USB_FS); | ||||||
| } | } | ||||||
|  | |||||||
| @ -96,6 +96,7 @@ void furi_hal_clock_init() { | |||||||
|     LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_DMAMUX1); |     LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_DMAMUX1); | ||||||
|     LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_DMA1); |     LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_DMA1); | ||||||
|     LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_I2C1); |     LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_I2C1); | ||||||
|  |     LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_SPI2); | ||||||
| 
 | 
 | ||||||
|     // AHB2
 |     // AHB2
 | ||||||
|     LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOA); |     LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOA); | ||||||
| @ -104,6 +105,7 @@ void furi_hal_clock_init() { | |||||||
|     LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOD); |     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_GPIOE); | ||||||
|     LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOH); |     LL_AHB2_GRP1_EnableClock(LL_AHB2_GRP1_PERIPH_GPIOH); | ||||||
|  |     LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_SPI1); | ||||||
| 
 | 
 | ||||||
|     // APB1
 |     // APB1
 | ||||||
|     LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_RTCAPB); |     LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_RTCAPB); | ||||||
|  | |||||||
| @ -485,7 +485,7 @@ static void furi_hal_irda_async_tx_free_resources(void) { | |||||||
|     furi_assert((furi_hal_irda_state == IrdaStateIdle) || (furi_hal_irda_state == IrdaStateAsyncTxStopped)); |     furi_assert((furi_hal_irda_state == IrdaStateIdle) || (furi_hal_irda_state == IrdaStateAsyncTxStopped)); | ||||||
|     osStatus_t status; |     osStatus_t status; | ||||||
| 
 | 
 | ||||||
|     hal_gpio_init_ex(&gpio_irda_tx, GpioModeOutputOpenDrain, GpioPullDown, GpioSpeedLow, 0); |     hal_gpio_init(&gpio_irda_tx, GpioModeOutputOpenDrain, GpioPullDown, GpioSpeedLow); | ||||||
|     furi_hal_interrupt_set_dma_channel_isr(DMA1, LL_DMA_CHANNEL_1, NULL); |     furi_hal_interrupt_set_dma_channel_isr(DMA1, LL_DMA_CHANNEL_1, NULL); | ||||||
|     furi_hal_interrupt_set_dma_channel_isr(DMA1, LL_DMA_CHANNEL_2, NULL); |     furi_hal_interrupt_set_dma_channel_isr(DMA1, LL_DMA_CHANNEL_2, NULL); | ||||||
|     LL_TIM_DeInit(TIM1); |     LL_TIM_DeInit(TIM1); | ||||||
|  | |||||||
| @ -27,7 +27,7 @@ void furi_hal_rfid_pins_emulate() { | |||||||
| 
 | 
 | ||||||
|     // pull pin to timer out
 |     // pull pin to timer out
 | ||||||
|     hal_gpio_init_ex( |     hal_gpio_init_ex( | ||||||
|         &gpio_rfid_pull, GpioModeAltFunctionPushPull, GpioSpeedLow, GpioPullNo, GpioAltFn1TIM2); |         &gpio_rfid_pull, GpioModeAltFunctionPushPull, GpioPullNo, GpioSpeedLow, GpioAltFn1TIM2); | ||||||
| 
 | 
 | ||||||
|     // pull rfid antenna from carrier side
 |     // pull rfid antenna from carrier side
 | ||||||
|     hal_gpio_init(&gpio_rfid_carrier_out, GpioModeOutputPushPull, GpioSpeedLow, GpioPullNo); |     hal_gpio_init(&gpio_rfid_carrier_out, GpioModeOutputPushPull, GpioSpeedLow, GpioPullNo); | ||||||
| @ -47,8 +47,8 @@ void furi_hal_rfid_pins_read() { | |||||||
|     hal_gpio_init_ex( |     hal_gpio_init_ex( | ||||||
|         &gpio_rfid_carrier_out, |         &gpio_rfid_carrier_out, | ||||||
|         GpioModeAltFunctionPushPull, |         GpioModeAltFunctionPushPull, | ||||||
|         GpioSpeedLow, |  | ||||||
|         GpioPullNo, |         GpioPullNo, | ||||||
|  |         GpioSpeedLow, | ||||||
|         GpioAltFn1TIM1); |         GpioAltFn1TIM1); | ||||||
| 
 | 
 | ||||||
|     // comparator in
 |     // comparator in
 | ||||||
|  | |||||||
| @ -1,100 +1,85 @@ | |||||||
| #include <furi-hal-spi-config.h> | #include <furi-hal-spi-config.h> | ||||||
| #include <furi-hal-resources.h> | #include <furi-hal-resources.h> | ||||||
| 
 | 
 | ||||||
| extern SPI_HandleTypeDef SPI_R; | #define SPI_R SPI1 | ||||||
| extern SPI_HandleTypeDef SPI_D; | #define SPI_D SPI2 | ||||||
| 
 | 
 | ||||||
| const SPI_InitTypeDef furi_hal_spi_config_nfc = { | const LL_SPI_InitTypeDef furi_hal_spi_config_nfc = { | ||||||
|     .Mode = SPI_MODE_MASTER, |     .Mode = LL_SPI_MODE_MASTER, | ||||||
|     .Direction = SPI_DIRECTION_2LINES, |     .TransferDirection = LL_SPI_FULL_DUPLEX, | ||||||
|     .DataSize = SPI_DATASIZE_8BIT, |     .DataWidth = LL_SPI_DATAWIDTH_8BIT, | ||||||
|     .CLKPolarity = SPI_POLARITY_LOW, |     .ClockPolarity = LL_SPI_POLARITY_LOW, | ||||||
|     .CLKPhase = SPI_PHASE_2EDGE, |     .ClockPhase = LL_SPI_PHASE_2EDGE, | ||||||
|     .NSS = SPI_NSS_SOFT, |     .NSS = LL_SPI_NSS_SOFT, | ||||||
|     .BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8, |     .BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV8, | ||||||
|     .FirstBit = SPI_FIRSTBIT_MSB, |     .BitOrder = LL_SPI_MSB_FIRST, | ||||||
|     .TIMode = SPI_TIMODE_DISABLE, |     .CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE, | ||||||
|     .CRCCalculation = SPI_CRCCALCULATION_DISABLE, |     .CRCPoly = 7, | ||||||
|     .CRCPolynomial = 7, |  | ||||||
|     .CRCLength = SPI_CRC_LENGTH_DATASIZE, |  | ||||||
|     .NSSPMode = SPI_NSS_PULSE_DISABLE, |  | ||||||
| }; | }; | ||||||
| 
 | 
 | ||||||
| const SPI_InitTypeDef furi_hal_spi_config_subghz = { | const LL_SPI_InitTypeDef furi_hal_spi_config_subghz = { | ||||||
|     .Mode = SPI_MODE_MASTER, |     .Mode = LL_SPI_MODE_MASTER, | ||||||
|     .Direction = SPI_DIRECTION_2LINES, |     .TransferDirection = LL_SPI_FULL_DUPLEX, | ||||||
|     .DataSize = SPI_DATASIZE_8BIT, |     .DataWidth = LL_SPI_DATAWIDTH_8BIT, | ||||||
|     .CLKPolarity = SPI_POLARITY_LOW, |     .ClockPolarity = LL_SPI_POLARITY_LOW, | ||||||
|     .CLKPhase = SPI_PHASE_1EDGE, |     .ClockPhase = LL_SPI_PHASE_1EDGE, | ||||||
|     .NSS = SPI_NSS_SOFT, |     .NSS = LL_SPI_NSS_SOFT, | ||||||
|     .BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8, |     .BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV8, | ||||||
|     .FirstBit = SPI_FIRSTBIT_MSB, |     .BitOrder = LL_SPI_MSB_FIRST, | ||||||
|     .TIMode = SPI_TIMODE_DISABLE, |     .CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE, | ||||||
|     .CRCCalculation = SPI_CRCCALCULATION_DISABLE, |     .CRCPoly = 7, | ||||||
|     .CRCPolynomial = 7, |  | ||||||
|     .CRCLength = SPI_CRC_LENGTH_DATASIZE, |  | ||||||
|     .NSSPMode = SPI_NSS_PULSE_DISABLE, |  | ||||||
| }; | }; | ||||||
| 
 | 
 | ||||||
| const SPI_InitTypeDef furi_hal_spi_config_display = { | const LL_SPI_InitTypeDef furi_hal_spi_config_display = { | ||||||
|     .Mode = SPI_MODE_MASTER, |     .Mode = LL_SPI_MODE_MASTER, | ||||||
|     .Direction = SPI_DIRECTION_2LINES, |     .TransferDirection = LL_SPI_FULL_DUPLEX, | ||||||
|     .DataSize = SPI_DATASIZE_8BIT, |     .DataWidth = LL_SPI_DATAWIDTH_8BIT, | ||||||
|     .CLKPolarity = SPI_POLARITY_LOW, |     .ClockPolarity = LL_SPI_POLARITY_LOW, | ||||||
|     .CLKPhase = SPI_PHASE_1EDGE, |     .ClockPhase = LL_SPI_PHASE_1EDGE, | ||||||
|     .NSS = SPI_NSS_SOFT, |     .NSS = LL_SPI_NSS_SOFT, | ||||||
|     .BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16, |     .BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV16, | ||||||
|     .FirstBit = SPI_FIRSTBIT_MSB, |     .BitOrder = LL_SPI_MSB_FIRST, | ||||||
|     .TIMode = SPI_TIMODE_DISABLE, |     .CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE, | ||||||
|     .CRCCalculation = SPI_CRCCALCULATION_DISABLE, |     .CRCPoly = 7, | ||||||
|     .CRCPolynomial = 7, |  | ||||||
|     .CRCLength = SPI_CRC_LENGTH_DATASIZE, |  | ||||||
|     .NSSPMode = SPI_NSS_PULSE_ENABLE, |  | ||||||
| }; | }; | ||||||
| 
 | 
 | ||||||
| /**
 | /**
 | ||||||
|  * SD Card in fast mode (after init) |  * SD Card in fast mode (after init) | ||||||
|  */ |  */ | ||||||
| const SPI_InitTypeDef furi_hal_spi_config_sd_fast = { | const LL_SPI_InitTypeDef furi_hal_spi_config_sd_fast = { | ||||||
|     .Mode = SPI_MODE_MASTER, |     .Mode = LL_SPI_MODE_MASTER, | ||||||
|     .Direction = SPI_DIRECTION_2LINES, |     .TransferDirection = LL_SPI_FULL_DUPLEX, | ||||||
|     .DataSize = SPI_DATASIZE_8BIT, |     .DataWidth = LL_SPI_DATAWIDTH_8BIT, | ||||||
|     .CLKPolarity = SPI_POLARITY_LOW, |     .ClockPolarity = LL_SPI_POLARITY_LOW, | ||||||
|     .CLKPhase = SPI_PHASE_1EDGE, |     .ClockPhase = LL_SPI_PHASE_1EDGE, | ||||||
|     .NSS = SPI_NSS_SOFT, |     .NSS = LL_SPI_NSS_SOFT, | ||||||
|     .BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2, |     .BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV2, | ||||||
|     .FirstBit = SPI_FIRSTBIT_MSB, |     .BitOrder = LL_SPI_MSB_FIRST, | ||||||
|     .TIMode = SPI_TIMODE_DISABLE, |     .CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE, | ||||||
|     .CRCCalculation = SPI_CRCCALCULATION_DISABLE, |     .CRCPoly = 7, | ||||||
|     .CRCPolynomial = 7, |  | ||||||
|     .CRCLength = SPI_CRC_LENGTH_DATASIZE, |  | ||||||
|     .NSSPMode = SPI_NSS_PULSE_ENABLE, |  | ||||||
| }; | }; | ||||||
| 
 | 
 | ||||||
| /**
 | /**
 | ||||||
|  * SD Card in slow mode (before init) |  * SD Card in slow mode (before init) | ||||||
|  */ |  */ | ||||||
| const SPI_InitTypeDef furi_hal_spi_config_sd_slow = { | const LL_SPI_InitTypeDef furi_hal_spi_config_sd_slow = { | ||||||
|     .Mode = SPI_MODE_MASTER, |     .Mode = LL_SPI_MODE_MASTER, | ||||||
|     .Direction = SPI_DIRECTION_2LINES, |     .TransferDirection = LL_SPI_FULL_DUPLEX, | ||||||
|     .DataSize = SPI_DATASIZE_8BIT, |     .DataWidth = LL_SPI_DATAWIDTH_8BIT, | ||||||
|     .CLKPolarity = SPI_POLARITY_LOW, |     .ClockPolarity = LL_SPI_POLARITY_LOW, | ||||||
|     .CLKPhase = SPI_PHASE_1EDGE, |     .ClockPhase = LL_SPI_PHASE_1EDGE, | ||||||
|     .NSS = SPI_NSS_SOFT, |     .NSS = LL_SPI_NSS_SOFT, | ||||||
|     .BaudRatePrescaler = SPI_BAUDRATEPRESCALER_32, |     .BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV32, | ||||||
|     .FirstBit = SPI_FIRSTBIT_MSB, |     .BitOrder = LL_SPI_MSB_FIRST, | ||||||
|     .TIMode = SPI_TIMODE_DISABLE, |     .CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE, | ||||||
|     .CRCCalculation = SPI_CRCCALCULATION_DISABLE, |     .CRCPoly = 7, | ||||||
|     .CRCPolynomial = 7, |  | ||||||
|     .CRCLength = SPI_CRC_LENGTH_DATASIZE, |  | ||||||
|     .NSSPMode = SPI_NSS_PULSE_ENABLE, |  | ||||||
| }; | }; | ||||||
| 
 | 
 | ||||||
| osMutexId_t spi_mutex_d = NULL; | osMutexId_t spi_mutex_d = NULL; | ||||||
| osMutexId_t spi_mutex_r = NULL; | osMutexId_t spi_mutex_r = NULL; | ||||||
| 
 | 
 | ||||||
| const FuriHalSpiBus spi_r = { | const FuriHalSpiBus spi_r = { | ||||||
|     .spi=&SPI_R, |     .spi=SPI_R, | ||||||
|     .mutex=&spi_mutex_r, |     .mutex=&spi_mutex_r, | ||||||
|     .miso=&gpio_spi_r_miso, |     .miso=&gpio_spi_r_miso, | ||||||
|     .mosi=&gpio_spi_r_mosi, |     .mosi=&gpio_spi_r_mosi, | ||||||
| @ -102,7 +87,7 @@ const FuriHalSpiBus spi_r = { | |||||||
| }; | }; | ||||||
| 
 | 
 | ||||||
| const FuriHalSpiBus spi_d = { | const FuriHalSpiBus spi_d = { | ||||||
|     .spi=&SPI_D, |     .spi=SPI_D, | ||||||
|     .mutex=&spi_mutex_d, |     .mutex=&spi_mutex_d, | ||||||
|     .miso=&gpio_spi_d_miso, |     .miso=&gpio_spi_d_miso, | ||||||
|     .mosi=&gpio_spi_d_mosi, |     .mosi=&gpio_spi_d_mosi, | ||||||
|  | |||||||
| @ -1,23 +1,24 @@ | |||||||
| #pragma once | #pragma once | ||||||
| 
 | 
 | ||||||
| #include <furi-hal-gpio.h> | #include <furi-hal-gpio.h> | ||||||
|  | #include <stm32wbxx_ll_spi.h> | ||||||
| #include <cmsis_os2.h> | #include <cmsis_os2.h> | ||||||
| 
 | 
 | ||||||
| #ifdef __cplusplus | #ifdef __cplusplus | ||||||
| extern "C" { | extern "C" { | ||||||
| #endif | #endif | ||||||
| 
 | 
 | ||||||
| extern const SPI_InitTypeDef furi_hal_spi_config_nfc; | extern const LL_SPI_InitTypeDef furi_hal_spi_config_nfc; | ||||||
| extern const SPI_InitTypeDef furi_hal_spi_config_subghz; | extern const LL_SPI_InitTypeDef furi_hal_spi_config_subghz; | ||||||
| extern const SPI_InitTypeDef furi_hal_spi_config_display; | extern const LL_SPI_InitTypeDef furi_hal_spi_config_display; | ||||||
| extern const SPI_InitTypeDef furi_hal_spi_config_sd_fast; | extern const LL_SPI_InitTypeDef furi_hal_spi_config_sd_fast; | ||||||
| extern const SPI_InitTypeDef furi_hal_spi_config_sd_slow; | extern const LL_SPI_InitTypeDef furi_hal_spi_config_sd_slow; | ||||||
| 
 | 
 | ||||||
| /** FURI HAL SPI BUS handler
 | /** FURI HAL SPI BUS handler
 | ||||||
|  * Structure content may change at some point |  * Structure content may change at some point | ||||||
|  */ |  */ | ||||||
| typedef struct { | typedef struct { | ||||||
|     const SPI_HandleTypeDef* spi; |     const SPI_TypeDef* spi; | ||||||
|     const osMutexId_t* mutex; |     const osMutexId_t* mutex; | ||||||
|     const GpioPin* miso; |     const GpioPin* miso; | ||||||
|     const GpioPin* mosi; |     const GpioPin* mosi; | ||||||
| @ -29,7 +30,7 @@ typedef struct { | |||||||
|  */ |  */ | ||||||
| typedef struct { | typedef struct { | ||||||
|     const FuriHalSpiBus* bus; |     const FuriHalSpiBus* bus; | ||||||
|     const SPI_InitTypeDef* config; |     const LL_SPI_InitTypeDef* config; | ||||||
|     const GpioPin* chip_select; |     const GpioPin* chip_select; | ||||||
| } FuriHalSpiDevice; | } FuriHalSpiDevice; | ||||||
| 
 | 
 | ||||||
| @ -57,11 +58,6 @@ extern const FuriHalSpiBus spi_d; | |||||||
| /** Furi Hal Spi devices */ | /** Furi Hal Spi devices */ | ||||||
| extern const FuriHalSpiDevice furi_hal_spi_devices[FuriHalSpiDeviceIdMax]; | extern const FuriHalSpiDevice furi_hal_spi_devices[FuriHalSpiDeviceIdMax]; | ||||||
| 
 | 
 | ||||||
| typedef struct { |  | ||||||
|     const FuriHalSpiBus* bus; |  | ||||||
|     const SPI_InitTypeDef config; |  | ||||||
| } SPIDevice; |  | ||||||
| 
 |  | ||||||
| #ifdef __cplusplus | #ifdef __cplusplus | ||||||
| } | } | ||||||
| #endif | #endif | ||||||
| @ -1,12 +1,13 @@ | |||||||
| #include "furi-hal-spi.h" | #include "furi-hal-spi.h" | ||||||
| #include <furi-hal-resources.h> | #include "furi-hal-resources.h" | ||||||
|  | 
 | ||||||
| #include <stdbool.h> | #include <stdbool.h> | ||||||
| #include <string.h> | #include <string.h> | ||||||
| #include <spi.h> |  | ||||||
| #include <furi.h> | #include <furi.h> | ||||||
| 
 | 
 | ||||||
| 
 | #include <stm32wbxx_ll_spi.h> | ||||||
| extern void Enable_SPI(SPI_HandleTypeDef* spi); | #include <stm32wbxx_ll_utils.h> | ||||||
|  | #include <stm32wbxx_ll_cortex.h> | ||||||
| 
 | 
 | ||||||
| void furi_hal_spi_init() { | void furi_hal_spi_init() { | ||||||
|     // Spi structure is const, but mutex is not
 |     // Spi structure is const, but mutex is not
 | ||||||
| @ -15,6 +16,7 @@ void furi_hal_spi_init() { | |||||||
|     *(osMutexId_t*)spi_d.mutex = osMutexNew(NULL); |     *(osMutexId_t*)spi_d.mutex = osMutexNew(NULL); | ||||||
|     // 
 |     // 
 | ||||||
|     for (size_t i=0; i<FuriHalSpiDeviceIdMax; ++i) { |     for (size_t i=0; i<FuriHalSpiDeviceIdMax; ++i) { | ||||||
|  |         hal_gpio_write(furi_hal_spi_devices[i].chip_select, true); | ||||||
|         hal_gpio_init( |         hal_gpio_init( | ||||||
|             furi_hal_spi_devices[i].chip_select, |             furi_hal_spi_devices[i].chip_select, | ||||||
|             GpioModeOutputPushPull, |             GpioModeOutputPushPull, | ||||||
| @ -22,41 +24,43 @@ void furi_hal_spi_init() { | |||||||
|             GpioSpeedVeryHigh |             GpioSpeedVeryHigh | ||||||
|         ); |         ); | ||||||
|     } |     } | ||||||
|  | 
 | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_r_miso, GpioModeAltFunctionPushPull, GpioPullNo, GpioSpeedVeryHigh, GpioAltFn5SPI1); | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_r_mosi, GpioModeAltFunctionPushPull, GpioPullNo, GpioSpeedVeryHigh, GpioAltFn5SPI1); | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_r_sck, GpioModeAltFunctionPushPull, GpioPullNo, GpioSpeedVeryHigh, GpioAltFn5SPI1); | ||||||
|  | 
 | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_d_miso, GpioModeAltFunctionPushPull, GpioPullUp, GpioSpeedVeryHigh, GpioAltFn5SPI2); | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_d_mosi, GpioModeAltFunctionPushPull, GpioPullUp, GpioSpeedVeryHigh, GpioAltFn5SPI2); | ||||||
|  |     hal_gpio_init_ex(&gpio_spi_d_sck, GpioModeAltFunctionPushPull, GpioPullUp, GpioSpeedVeryHigh, GpioAltFn5SPI2); | ||||||
|  | 
 | ||||||
|     FURI_LOG_I("FuriHalSpi", "Init OK"); |     FURI_LOG_I("FuriHalSpi", "Init OK"); | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void furi_hal_spi_bus_lock(const FuriHalSpiBus* bus) { | void furi_hal_spi_bus_lock(const FuriHalSpiBus* bus) { | ||||||
|     furi_assert(bus); |     furi_assert(bus); | ||||||
|     if (bus->mutex) { |     furi_check(osMutexAcquire(*bus->mutex, osWaitForever) == osOK); | ||||||
|         osMutexAcquire(*bus->mutex, osWaitForever); |  | ||||||
|     } |  | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void furi_hal_spi_bus_unlock(const FuriHalSpiBus* bus) { | void furi_hal_spi_bus_unlock(const FuriHalSpiBus* bus) { | ||||||
|     furi_assert(bus); |     furi_assert(bus); | ||||||
|     if (bus->mutex) { |     furi_check(osMutexRelease(*bus->mutex) == osOK); | ||||||
|         osMutexRelease(*bus->mutex); |  | ||||||
|     } |  | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void furi_hal_spi_bus_configure(const FuriHalSpiBus* bus, const SPI_InitTypeDef* config) { | void furi_hal_spi_bus_configure(const FuriHalSpiBus* bus, const LL_SPI_InitTypeDef* config) { | ||||||
|     furi_assert(bus); |     furi_assert(bus); | ||||||
| 
 | 
 | ||||||
|     if(memcmp(&bus->spi->Init, config, sizeof(SPI_InitTypeDef))) { |     LL_SPI_DeInit((SPI_TypeDef*)bus->spi); | ||||||
|         memcpy((SPI_InitTypeDef*)&bus->spi->Init, config, sizeof(SPI_InitTypeDef)); |     LL_SPI_Init((SPI_TypeDef*)bus->spi, (LL_SPI_InitTypeDef*)config); | ||||||
|         if(HAL_SPI_Init((SPI_HandleTypeDef*)bus->spi) != HAL_OK) { |     LL_SPI_SetRxFIFOThreshold((SPI_TypeDef*)bus->spi, LL_SPI_RX_FIFO_TH_QUARTER); | ||||||
|             Error_Handler(); |     LL_SPI_Enable((SPI_TypeDef*)bus->spi); | ||||||
|         } |  | ||||||
|         Enable_SPI((SPI_HandleTypeDef*)bus->spi); |  | ||||||
|     } |  | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void furi_hal_spi_bus_reset(const FuriHalSpiBus* bus) { | void furi_hal_spi_bus_end_txrx(const FuriHalSpiBus* bus, uint32_t timeout) { | ||||||
|     furi_assert(bus); |     while(LL_SPI_GetTxFIFOLevel((SPI_TypeDef *)bus->spi) != LL_SPI_TX_FIFO_EMPTY); | ||||||
| 
 |     while(LL_SPI_IsActiveFlag_BSY((SPI_TypeDef *)bus->spi)); | ||||||
|     HAL_SPI_DeInit((SPI_HandleTypeDef*)bus->spi); |     while(LL_SPI_GetRxFIFOLevel((SPI_TypeDef *)bus->spi) != LL_SPI_RX_FIFO_EMPTY) { | ||||||
|     HAL_SPI_Init((SPI_HandleTypeDef*)bus->spi); |         LL_SPI_ReceiveData8((SPI_TypeDef *)bus->spi); | ||||||
|     Enable_SPI((SPI_HandleTypeDef*)bus->spi); |     } | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| bool furi_hal_spi_bus_rx(const FuriHalSpiBus* bus, uint8_t* buffer, size_t size, uint32_t timeout) { | bool furi_hal_spi_bus_rx(const FuriHalSpiBus* bus, uint8_t* buffer, size_t size, uint32_t timeout) { | ||||||
| @ -64,19 +68,27 @@ bool furi_hal_spi_bus_rx(const FuriHalSpiBus* bus, uint8_t* buffer, size_t size, | |||||||
|     furi_assert(buffer); |     furi_assert(buffer); | ||||||
|     furi_assert(size > 0); |     furi_assert(size > 0); | ||||||
| 
 | 
 | ||||||
|     HAL_StatusTypeDef ret = HAL_SPI_Receive((SPI_HandleTypeDef *)bus->spi, buffer, size, HAL_MAX_DELAY); |     return furi_hal_spi_bus_trx(bus, buffer, buffer, size, timeout); | ||||||
| 
 |  | ||||||
|     return ret == HAL_OK; |  | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| bool furi_hal_spi_bus_tx(const FuriHalSpiBus* bus, uint8_t* buffer, size_t size, uint32_t timeout) { | bool furi_hal_spi_bus_tx(const FuriHalSpiBus* bus, uint8_t* buffer, size_t size, uint32_t timeout) { | ||||||
|     furi_assert(bus); |     furi_assert(bus); | ||||||
|     furi_assert(buffer); |     furi_assert(buffer); | ||||||
|     furi_assert(size > 0); |     furi_assert(size > 0); | ||||||
|  |     bool ret = true; | ||||||
| 
 | 
 | ||||||
|     HAL_StatusTypeDef ret = HAL_SPI_Transmit((SPI_HandleTypeDef *)bus->spi, buffer, size, HAL_MAX_DELAY); |     while(size > 0) { | ||||||
|  |         if (LL_SPI_IsActiveFlag_TXE((SPI_TypeDef *)bus->spi)) { | ||||||
|  |             LL_SPI_TransmitData8((SPI_TypeDef *)bus->spi, *buffer); | ||||||
|  |             buffer++; | ||||||
|  |             size--; | ||||||
|  |         } | ||||||
|  |     } | ||||||
| 
 | 
 | ||||||
|     return ret == HAL_OK; |     furi_hal_spi_bus_end_txrx(bus, timeout); | ||||||
|  |     LL_SPI_ClearFlag_OVR((SPI_TypeDef *)bus->spi); | ||||||
|  | 
 | ||||||
|  |     return ret; | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| bool furi_hal_spi_bus_trx(const FuriHalSpiBus* bus, uint8_t* tx_buffer, uint8_t* rx_buffer, size_t size, uint32_t timeout) { | bool furi_hal_spi_bus_trx(const FuriHalSpiBus* bus, uint8_t* tx_buffer, uint8_t* rx_buffer, size_t size, uint32_t timeout) { | ||||||
| @ -85,9 +97,36 @@ bool furi_hal_spi_bus_trx(const FuriHalSpiBus* bus, uint8_t* tx_buffer, uint8_t* | |||||||
|     furi_assert(rx_buffer); |     furi_assert(rx_buffer); | ||||||
|     furi_assert(size > 0); |     furi_assert(size > 0); | ||||||
| 
 | 
 | ||||||
|     HAL_StatusTypeDef ret = HAL_SPI_TransmitReceive((SPI_HandleTypeDef *)bus->spi, tx_buffer, rx_buffer, size, HAL_MAX_DELAY); |     bool ret = true; | ||||||
|  |     size_t tx_size = size; | ||||||
|  |     bool tx_allowed = true; | ||||||
| 
 | 
 | ||||||
|     return ret == HAL_OK; |     while(size > 0) { | ||||||
|  |         if(tx_size > 0 && LL_SPI_IsActiveFlag_TXE((SPI_TypeDef *)bus->spi) && tx_allowed) { | ||||||
|  |             LL_SPI_TransmitData8((SPI_TypeDef *)bus->spi, *tx_buffer); | ||||||
|  |             tx_buffer++; | ||||||
|  |             tx_size--; | ||||||
|  |             tx_allowed = false; | ||||||
|  |         } | ||||||
|  |          | ||||||
|  |         if(LL_SPI_IsActiveFlag_RXNE((SPI_TypeDef *)bus->spi)) { | ||||||
|  |             *rx_buffer = LL_SPI_ReceiveData8((SPI_TypeDef *)bus->spi); | ||||||
|  |             rx_buffer++; | ||||||
|  |             size--; | ||||||
|  |             tx_allowed = true; | ||||||
|  |         } | ||||||
|  |     } | ||||||
|  | 
 | ||||||
|  |     furi_hal_spi_bus_end_txrx(bus, timeout); | ||||||
|  | 
 | ||||||
|  |     return ret; | ||||||
|  | } | ||||||
|  | 
 | ||||||
|  | void furi_hal_spi_device_configure(const FuriHalSpiDevice* device) { | ||||||
|  |     furi_assert(device); | ||||||
|  |     furi_assert(device->config); | ||||||
|  | 
 | ||||||
|  |     furi_hal_spi_bus_configure(device->bus, device->config); | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| const FuriHalSpiDevice* furi_hal_spi_device_get(FuriHalSpiDeviceId device_id) { | const FuriHalSpiDevice* furi_hal_spi_device_get(FuriHalSpiDeviceId device_id) { | ||||||
| @ -96,14 +135,7 @@ const FuriHalSpiDevice* furi_hal_spi_device_get(FuriHalSpiDeviceId device_id) { | |||||||
|     const FuriHalSpiDevice* device = &furi_hal_spi_devices[device_id]; |     const FuriHalSpiDevice* device = &furi_hal_spi_devices[device_id]; | ||||||
|     assert(device); |     assert(device); | ||||||
|     furi_hal_spi_bus_lock(device->bus); |     furi_hal_spi_bus_lock(device->bus); | ||||||
| 
 |     furi_hal_spi_device_configure(device); | ||||||
|     if (device->config) { |  | ||||||
|         memcpy((SPI_InitTypeDef*)&device->bus->spi->Init, device->config, sizeof(SPI_InitTypeDef)); |  | ||||||
|         if(HAL_SPI_Init((SPI_HandleTypeDef *)device->bus->spi) != HAL_OK) { |  | ||||||
|             Error_Handler(); |  | ||||||
|         } |  | ||||||
|         Enable_SPI((SPI_HandleTypeDef *)device->bus->spi); |  | ||||||
|     } |  | ||||||
| 
 | 
 | ||||||
|     return device; |     return device; | ||||||
| } | } | ||||||
| @ -121,7 +153,7 @@ bool furi_hal_spi_device_rx(const FuriHalSpiDevice* device, uint8_t* buffer, siz | |||||||
|         hal_gpio_write(device->chip_select, false); |         hal_gpio_write(device->chip_select, false); | ||||||
|     } |     } | ||||||
| 
 | 
 | ||||||
|     bool ret = furi_hal_spi_bus_rx(device->bus, buffer, size, HAL_MAX_DELAY); |     bool ret = furi_hal_spi_bus_rx(device->bus, buffer, size, timeout); | ||||||
| 
 | 
 | ||||||
|     if (device->chip_select) { |     if (device->chip_select) { | ||||||
|         hal_gpio_write(device->chip_select, true); |         hal_gpio_write(device->chip_select, true); | ||||||
| @ -139,7 +171,7 @@ bool furi_hal_spi_device_tx(const FuriHalSpiDevice* device, uint8_t* buffer, siz | |||||||
|         hal_gpio_write(device->chip_select, false); |         hal_gpio_write(device->chip_select, false); | ||||||
|     } |     } | ||||||
| 
 | 
 | ||||||
|     bool ret = furi_hal_spi_bus_tx(device->bus, buffer, size, HAL_MAX_DELAY); |     bool ret = furi_hal_spi_bus_tx(device->bus, buffer, size, timeout); | ||||||
| 
 | 
 | ||||||
|     if (device->chip_select) { |     if (device->chip_select) { | ||||||
|         hal_gpio_write(device->chip_select, true); |         hal_gpio_write(device->chip_select, true); | ||||||
| @ -158,7 +190,7 @@ bool furi_hal_spi_device_trx(const FuriHalSpiDevice* device, uint8_t* tx_buffer, | |||||||
|         hal_gpio_write(device->chip_select, false); |         hal_gpio_write(device->chip_select, false); | ||||||
|     } |     } | ||||||
| 
 | 
 | ||||||
|     bool ret = furi_hal_spi_bus_trx(device->bus, tx_buffer, rx_buffer, size, HAL_MAX_DELAY); |     bool ret = furi_hal_spi_bus_trx(device->bus, tx_buffer, rx_buffer, size, timeout); | ||||||
| 
 | 
 | ||||||
|     if (device->chip_select) { |     if (device->chip_select) { | ||||||
|         hal_gpio_write(device->chip_select, true); |         hal_gpio_write(device->chip_select, true); | ||||||
|  | |||||||
| @ -30,13 +30,7 @@ void furi_hal_spi_bus_unlock(const FuriHalSpiBus* bus); | |||||||
|  * @param bus - spi bus handler |  * @param bus - spi bus handler | ||||||
|  * @param config - spi configuration structure |  * @param config - spi configuration structure | ||||||
|  */ |  */ | ||||||
| void furi_hal_spi_bus_configure(const FuriHalSpiBus* bus, const SPI_InitTypeDef* config); | void furi_hal_spi_bus_configure(const FuriHalSpiBus* bus, const LL_SPI_InitTypeDef* config); | ||||||
| 
 |  | ||||||
| /**
 |  | ||||||
|  * Reset SPI bus |  | ||||||
|  * @param bus - spi bus handler |  | ||||||
|  */ |  | ||||||
| void furi_hal_spi_bus_reset(const FuriHalSpiBus* bus); |  | ||||||
| 
 | 
 | ||||||
| /** SPI Receive
 | /** SPI Receive
 | ||||||
|  * @param bus - spi bus handler |  * @param bus - spi bus handler | ||||||
| @ -65,6 +59,11 @@ bool furi_hal_spi_bus_trx(const FuriHalSpiBus* bus, uint8_t* tx_buffer, uint8_t* | |||||||
| 
 | 
 | ||||||
| /* Device Level API */ | /* Device Level API */ | ||||||
| 
 | 
 | ||||||
|  | /** Reconfigure SPI bus for device
 | ||||||
|  |  * @param device - device description | ||||||
|  |  */ | ||||||
|  | void furi_hal_spi_device_configure(const FuriHalSpiDevice* device); | ||||||
|  | 
 | ||||||
| /** Get Device handle
 | /** Get Device handle
 | ||||||
|  * And lock access to the corresponding SPI BUS |  * And lock access to the corresponding SPI BUS | ||||||
|  * @param device_id - device identifier |  * @param device_id - device identifier | ||||||
| @ -104,16 +103,6 @@ bool furi_hal_spi_device_tx(const FuriHalSpiDevice* device, uint8_t* buffer, siz | |||||||
| bool furi_hal_spi_device_trx(const FuriHalSpiDevice* device, uint8_t* tx_buffer, uint8_t* rx_buffer, size_t size, uint32_t timeout); | bool furi_hal_spi_device_trx(const FuriHalSpiDevice* device, uint8_t* tx_buffer, uint8_t* rx_buffer, size_t size, uint32_t timeout); | ||||||
| 
 | 
 | ||||||
| 
 | 
 | ||||||
| /**
 |  | ||||||
|  * Lock SPI device bus and apply config if needed |  | ||||||
|  */ |  | ||||||
| void furi_hal_spi_lock_device(const SPIDevice* device); |  | ||||||
| 
 |  | ||||||
| /**
 |  | ||||||
|  * Unlock SPI device bus |  | ||||||
|  */ |  | ||||||
| void furi_hal_spi_unlock_device(const SPIDevice* device); |  | ||||||
| 
 |  | ||||||
| #ifdef __cplusplus | #ifdef __cplusplus | ||||||
| } | } | ||||||
| #endif | #endif | ||||||
| @ -1,14 +1,11 @@ | |||||||
| #include <furi-hal.h> | #include <furi-hal.h> | ||||||
| 
 | 
 | ||||||
| #include <adc.h> |  | ||||||
| #include <aes.h> | #include <aes.h> | ||||||
| #include <comp.h> | #include <comp.h> | ||||||
| #include <crc.h> |  | ||||||
| #include <pka.h> | #include <pka.h> | ||||||
| #include <rf.h> | #include <rf.h> | ||||||
| #include <rng.h> | #include <rng.h> | ||||||
| #include <rtc.h> | #include <rtc.h> | ||||||
| #include <spi.h> |  | ||||||
| #include <tim.h> | #include <tim.h> | ||||||
| #include <usb_device.h> | #include <usb_device.h> | ||||||
| #include <gpio.h> | #include <gpio.h> | ||||||
| @ -27,13 +24,6 @@ void furi_hal_init() { | |||||||
|     furi_hal_boot_init(); |     furi_hal_boot_init(); | ||||||
|     furi_hal_version_init(); |     furi_hal_version_init(); | ||||||
| 
 | 
 | ||||||
|     MX_ADC1_Init(); |  | ||||||
|     FURI_LOG_I("HAL", "ADC1 OK"); |  | ||||||
| 
 |  | ||||||
|     MX_SPI1_Init(); |  | ||||||
|     FURI_LOG_I("HAL", "SPI1 OK"); |  | ||||||
|     MX_SPI2_Init(); |  | ||||||
|     FURI_LOG_I("HAL", "SPI2 OK"); |  | ||||||
|     furi_hal_spi_init(); |     furi_hal_spi_init(); | ||||||
| 
 | 
 | ||||||
|     MX_TIM1_Init(); |     MX_TIM1_Init(); | ||||||
| @ -54,8 +44,6 @@ void furi_hal_init() { | |||||||
|     FURI_LOG_I("HAL", "AES1 OK"); |     FURI_LOG_I("HAL", "AES1 OK"); | ||||||
|     MX_AES2_Init(); |     MX_AES2_Init(); | ||||||
|     FURI_LOG_I("HAL", "AES2 OK"); |     FURI_LOG_I("HAL", "AES2 OK"); | ||||||
|     MX_CRC_Init(); |  | ||||||
|     FURI_LOG_I("HAL", "CRC OK"); |  | ||||||
| 
 | 
 | ||||||
|     // VCP + USB
 |     // VCP + USB
 | ||||||
|     furi_hal_vcp_init(); |     furi_hal_vcp_init(); | ||||||
|  | |||||||
| @ -44,13 +44,9 @@ FURI_HAL_DIR = $(TARGET_DIR) | |||||||
| CUBE_DIR		= ../lib/STM32CubeWB | CUBE_DIR		= ../lib/STM32CubeWB | ||||||
| C_SOURCES		+= \
 | C_SOURCES		+= \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc.c \
 |  | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_adc_ex.c \
 |  | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_comp.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_comp.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_cortex.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_cryp.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_crc.c \
 |  | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_crc_ex.c \
 |  | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_exti.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_exti.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash_ex.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_flash_ex.c \
 | ||||||
| @ -67,20 +63,19 @@ C_SOURCES		+= \ | |||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rng.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rng.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc_ex.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_rtc_ex.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi.c \
 |  | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_spi_ex.c \
 |  | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim_ex.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_hal_tim_ex.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_adc.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_adc.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_dma.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_dma.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_gpio.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_gpio.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_i2c.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_i2c.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_rcc.c \
 |  | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_tim.c \
 |  | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_lptim.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_lptim.c \
 | ||||||
|  | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_rcc.c \
 | ||||||
|  | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_spi.c \
 | ||||||
|  | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_tim.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_usart.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_usart.c \
 | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_utils.c \
 |  | ||||||
| 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_usb.c \
 | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_usb.c \
 | ||||||
|  | 	$(CUBE_DIR)/Drivers/STM32WBxx_HAL_Driver/Src/stm32wbxx_ll_utils.c \
 | ||||||
| 	$(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/croutine.c \
 | 	$(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/croutine.c \
 | ||||||
| 	$(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/event_groups.c \
 | 	$(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/event_groups.c \
 | ||||||
| 	$(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/list.c \
 | 	$(CUBE_DIR)/Middlewares/Third_Party/FreeRTOS/Source/list.c \
 | ||||||
|  | |||||||
| @ -68,10 +68,12 @@ HAL_StatusTypeDef platformSpiTxRx(const uint8_t *txBuf, uint8_t *rxBuf, uint16_t | |||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void platformProtectST25RComm() { | void platformProtectST25RComm() { | ||||||
|  |     furi_assert(platform_st25r3916 == NULL); | ||||||
|     platform_st25r3916 = (FuriHalSpiDevice*)furi_hal_spi_device_get(FuriHalSpiDeviceIdNfc); |     platform_st25r3916 = (FuriHalSpiDevice*)furi_hal_spi_device_get(FuriHalSpiDeviceIdNfc); | ||||||
| } | } | ||||||
| 
 | 
 | ||||||
| void platformUnprotectST25RComm() { | void platformUnprotectST25RComm() { | ||||||
|     furi_assert(platform_st25r3916); |     furi_assert(platform_st25r3916); | ||||||
|     furi_hal_spi_device_return(platform_st25r3916); |     furi_hal_spi_device_return(platform_st25r3916); | ||||||
|  |     platform_st25r3916 = NULL; | ||||||
| } | } | ||||||
|  | |||||||
| @ -8,7 +8,6 @@ | |||||||
| #include <gpio.h> | #include <gpio.h> | ||||||
| #include "timer.h" | #include "timer.h" | ||||||
| #include "math.h" | #include "math.h" | ||||||
| #include "spi.h" |  | ||||||
| #include "main.h" | #include "main.h" | ||||||
| #include <furi-hal-gpio.h> | #include <furi-hal-gpio.h> | ||||||
| #include <furi-hal-light.h> | #include <furi-hal-light.h> | ||||||
|  | |||||||
		Loading…
	
	
			
			x
			
			
		
	
		Reference in New Issue
	
	Block a user
	 あく
						あく