2018-04-25 20:10:27 -03:00
|
|
|
/*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "hal.h"
|
|
|
|
|
|
|
|
#ifdef __cplusplus
|
|
|
|
extern "C" {
|
|
|
|
#endif
|
|
|
|
|
|
|
|
void stm32_timer_set_input_filter(stm32_tim_t *tim, uint8_t channel, uint8_t filter_mode);
|
2018-06-02 10:19:46 -03:00
|
|
|
void stm32_timer_set_channel_input(stm32_tim_t *tim, uint8_t channel, uint8_t input_source);
|
2018-04-25 20:10:27 -03:00
|
|
|
|
2018-05-30 07:15:43 -03:00
|
|
|
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
|
|
|
|
// print stack usage
|
|
|
|
void show_stack_usage(void);
|
|
|
|
#endif
|
2018-06-02 00:27:02 -03:00
|
|
|
|
|
|
|
// allocation functions in malloc.c
|
|
|
|
size_t mem_available(void);
|
|
|
|
void *malloc_dma(size_t size);
|
2021-05-29 16:47:40 -03:00
|
|
|
void *malloc_axi_sram(size_t size);
|
2019-02-17 07:23:34 -04:00
|
|
|
void *malloc_fastmem(size_t size);
|
2019-02-26 20:14:58 -04:00
|
|
|
thread_t *thread_create_alloc(size_t size, const char *name, tprio_t prio, tfunc_t pf, void *arg);
|
2018-06-02 10:19:46 -03:00
|
|
|
|
2021-01-22 06:32:30 -04:00
|
|
|
struct memory_region {
|
|
|
|
void *address;
|
|
|
|
uint32_t size;
|
|
|
|
uint32_t flags;
|
|
|
|
};
|
|
|
|
#if CH_CFG_USE_HEAP == TRUE
|
|
|
|
uint8_t malloc_get_heaps(memory_heap_t **_heaps, const struct memory_region **regions);
|
|
|
|
#endif
|
|
|
|
|
2018-06-16 04:43:28 -03:00
|
|
|
// flush all dcache
|
|
|
|
void memory_flush_all(void);
|
|
|
|
|
2018-06-14 02:31:33 -03:00
|
|
|
// UTC system clock handling
|
|
|
|
void stm32_set_utc_usec(uint64_t time_utc_usec);
|
|
|
|
uint64_t stm32_get_utc_usec(void);
|
2018-06-14 22:26:40 -03:00
|
|
|
|
|
|
|
// hook for FAT timestamps
|
|
|
|
uint32_t get_fattime(void);
|
2018-06-21 03:24:38 -03:00
|
|
|
|
|
|
|
// one-time programmable area
|
2021-04-28 23:40:59 -03:00
|
|
|
#if defined(FLASH_OTP_BASE)
|
|
|
|
#define OTP_BASE FLASH_OTP_BASE
|
|
|
|
#define OTP_SIZE (FLASH_OTP_END-FLASH_OTP_BASE)
|
|
|
|
#elif defined(STM32F4)
|
2018-06-21 03:24:38 -03:00
|
|
|
#define OTP_BASE 0x1fff7800
|
|
|
|
#define OTP_SIZE 512
|
|
|
|
#elif defined(STM32F7)
|
|
|
|
#define OTP_BASE 0x1ff0f000
|
|
|
|
#define OTP_SIZE 1024
|
|
|
|
#endif
|
2018-06-27 05:46:34 -03:00
|
|
|
|
|
|
|
enum rtc_boot_magic {
|
|
|
|
RTC_BOOT_OFF = 0,
|
|
|
|
RTC_BOOT_HOLD = 0xb0070001,
|
2019-05-26 22:45:30 -03:00
|
|
|
RTC_BOOT_FAST = 0xb0070002,
|
2019-10-25 22:41:26 -03:00
|
|
|
RTC_BOOT_CANBL = 0xb0080000, // ORd with 8 bit local node ID
|
|
|
|
RTC_BOOT_FWOK = 0xb0093a26 // indicates FW ran for 30s
|
2018-06-27 05:46:34 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// see if RTC registers is setup for a fast reboot
|
|
|
|
enum rtc_boot_magic check_fast_reboot(void);
|
|
|
|
|
|
|
|
// set RTC register for a fast reboot
|
|
|
|
void set_fast_reboot(enum rtc_boot_magic v);
|
2018-07-11 02:11:36 -03:00
|
|
|
|
|
|
|
// enable peripheral power if needed
|
|
|
|
void peripheral_power_enable(void);
|
2018-07-19 20:06:02 -03:00
|
|
|
|
|
|
|
// initialise allocation subsystem
|
|
|
|
void malloc_init(void);
|
2018-11-15 06:15:57 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
read mode of a pin. This allows a pin config to be read, changed and
|
|
|
|
then written back
|
|
|
|
*/
|
2021-09-19 03:37:09 -03:00
|
|
|
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4)
|
2018-11-15 06:15:57 -04:00
|
|
|
iomode_t palReadLineMode(ioline_t line);
|
2019-12-02 18:56:05 -04:00
|
|
|
|
|
|
|
enum PalPushPull {
|
|
|
|
PAL_PUSHPULL_NOPULL=0,
|
|
|
|
PAL_PUSHPULL_PULLUP=1,
|
|
|
|
PAL_PUSHPULL_PULLDOWN=2
|
|
|
|
};
|
|
|
|
|
|
|
|
void palLineSetPushPull(ioline_t line, enum PalPushPull pp);
|
2018-11-15 06:15:57 -04:00
|
|
|
#endif
|
|
|
|
|
2019-05-09 04:49:32 -03:00
|
|
|
// set n RTC backup registers starting at given idx
|
|
|
|
void set_rtc_backup(uint8_t idx, const uint32_t *v, uint8_t n);
|
2019-04-20 06:53:08 -03:00
|
|
|
|
2019-05-09 04:49:32 -03:00
|
|
|
// get RTC backup registers starting at given idx
|
|
|
|
void get_rtc_backup(uint8_t idx, uint32_t *v, uint8_t n);
|
2019-04-19 21:28:15 -03:00
|
|
|
|
2019-08-02 07:57:01 -03:00
|
|
|
void stm32_cacheBufferInvalidate(const void *p, size_t size);
|
|
|
|
void stm32_cacheBufferFlush(const void *p, size_t size);
|
|
|
|
|
2019-11-25 23:59:08 -04:00
|
|
|
#ifdef HAL_GPIO_PIN_FAULT
|
|
|
|
// printf for fault handlers
|
|
|
|
void fault_printf(const char *fmt, ...);
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// halt hook for printing panic message
|
|
|
|
void system_halt_hook(void);
|
|
|
|
|
2020-04-28 03:34:52 -03:00
|
|
|
// hook for stack overflow
|
|
|
|
void stack_overflow(thread_t *tp);
|
2020-11-29 15:53:49 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
check how much stack is free given a stack base. Assumes the fill
|
|
|
|
byte is 0x55
|
|
|
|
*/
|
|
|
|
uint32_t stack_free(void *stack_base);
|
|
|
|
|
2021-10-23 03:36:39 -03:00
|
|
|
// returns true is address in memory region
|
|
|
|
bool is_address_in_memory(void *addr);
|
|
|
|
|
|
|
|
// return the start of memory region that contains the address
|
|
|
|
void* get_addr_mem_region_start_addr(void *addr);
|
|
|
|
// return the end of memory region that contains the address
|
|
|
|
void* get_addr_mem_region_end_addr(void *addr);
|
|
|
|
|
|
|
|
// return the size of crash dump
|
|
|
|
uint32_t stm32_crash_dump_size(void);
|
2021-11-26 00:48:44 -04:00
|
|
|
uint32_t stm32_crash_dump_addr(void);
|
|
|
|
uint32_t stm32_crash_dump_max_size(void);
|
2021-10-23 03:36:39 -03:00
|
|
|
|
2021-10-23 05:30:25 -03:00
|
|
|
typedef enum {
|
|
|
|
Reset = 1,
|
|
|
|
NMI = 2,
|
|
|
|
HardFault = 3,
|
|
|
|
MemManage = 4,
|
|
|
|
BusFault = 5,
|
|
|
|
UsageFault = 6,
|
|
|
|
} FaultType;
|
|
|
|
|
|
|
|
// Record information about a fault
|
|
|
|
void save_fault_watchdog(uint16_t line, FaultType fault_type, uint32_t fault_addr, uint32_t lr);
|
2021-10-06 02:37:38 -03:00
|
|
|
/**
|
|
|
|
* Generates a block of random values, returns total values generated
|
|
|
|
* if nonblocking, for blocking returns if successful or not
|
|
|
|
*/
|
2021-10-06 03:30:38 -03:00
|
|
|
#if HAL_USE_HW_RNG && defined(RNG)
|
2021-10-06 02:37:38 -03:00
|
|
|
bool stm32_rand_generate_blocking(unsigned char* output, unsigned int sz, uint32_t timeout_us);
|
|
|
|
unsigned int stm32_rand_generate_nonblocking(unsigned char* output, unsigned int sz);
|
|
|
|
#endif
|
|
|
|
|
2022-02-18 17:31:53 -04:00
|
|
|
void stm32_flash_protect_flash(bool bootloader, bool protect);
|
|
|
|
void stm32_flash_unprotect_flash(void);
|
|
|
|
|
2020-11-29 15:53:49 -04:00
|
|
|
// allow stack view code to show free ISR stack
|
2020-11-29 18:10:21 -04:00
|
|
|
extern uint32_t __main_stack_base__;
|
|
|
|
extern uint32_t __main_stack_end__;
|
|
|
|
extern uint32_t __main_thread_stack_base__;
|
|
|
|
extern uint32_t __main_thread_stack_end__;
|
2020-11-29 15:53:49 -04:00
|
|
|
|
2018-04-25 20:10:27 -03:00
|
|
|
#ifdef __cplusplus
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|