mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: hwdef for SPRacingH7
hwdef for DevEBoxH7v2 pin definitions for STM32H750 add QSPI to DevEBox bootloader add external flash to DevEBox rename EXTERNAL_PROG_FLASH_MB to EXT_FLASH_SIZE_MB Add support for EXT_FLASH_RESERVE_START_KB and EXT_FLASH_RESERVE_END_KB Disable HAL_ENABLE_SAVE_PERSISTENT_PARAMS when there is no bootloader flash available relax storage health status with SD card backend don't check SD card health unless USE_POSIX binary sections rearranged on external ram manage RAMFUNC through ldscript and optimize function placement in external flash inline timer functions optimize placement of ChibiOS and functions in ITCM and AXI RAM fix chibios features on bootloader build with external flash change H750 memory layout increase line storage for SD card based parameters comment external flash linker script move vtables into DTCM update ram map for H757 enable crashdump support with external flash correct bootloader pins and generator on SPRacingH7/DevEBoxH7v2 setup external flash reserve regions allow different RAM_MAP for external flash on H750 and H757
This commit is contained in:
parent
960c0d0f8b
commit
48c21299f8
|
@ -24,7 +24,7 @@ void EventSource::signal(uint32_t evt_mask)
|
|||
ch_evt_src_.broadcastFlags(evt_mask);
|
||||
}
|
||||
|
||||
void EventSource::signalI(uint32_t evt_mask)
|
||||
__RAMFUNC__ void EventSource::signalI(uint32_t evt_mask)
|
||||
{
|
||||
chSysLockFromISR();
|
||||
ch_evt_src_.broadcastFlagsI(evt_mask);
|
||||
|
|
|
@ -27,7 +27,6 @@
|
|||
#include <stdio.h>
|
||||
#include "ch.h"
|
||||
#include "hal.h"
|
||||
#include "hrt.h"
|
||||
|
||||
class HAL_ChibiOS : public AP_HAL::HAL {
|
||||
public:
|
||||
|
|
|
@ -49,12 +49,12 @@ QSPIDesc QSPIDeviceManager::device_table[] = { HAL_QSPI_DEVICE_LIST };
|
|||
#define STR(x) #x
|
||||
|
||||
#if (STM32_QSPICLK % HAL_QSPI1_CLK)
|
||||
#error "QSPI Clock" STR(STM32_QSPICLK) " needs to be divisible by selected clock" STR(HAL_QSPI1_CLK)
|
||||
#error "QSPI Clock" XSTR(STM32_QSPICLK) " needs to be divisible by selected clock" XSTR(HAL_QSPI1_CLK)
|
||||
#endif
|
||||
|
||||
#if defined(STM32_WSPI_USE_QUADSPI2) && STM32_WSPI_USE_QUADSPI2
|
||||
#if (STM32_QSPICLK % HAL_QSPI2_CLK)
|
||||
#error "QSPI Clock" STR(STM32_QSPICLK) " needs to be divisible by selected clock" STR(HAL_QSPI2_CLK)
|
||||
#error "QSPI Clock" XSTR(STM32_QSPICLK) " needs to be divisible by selected clock" XSTR(HAL_QSPI2_CLK)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
|
|
@ -178,7 +178,7 @@ void RCOutput::rcout_thread()
|
|||
}
|
||||
}
|
||||
|
||||
void RCOutput::dshot_update_tick(void* p)
|
||||
__RAMFUNC__ void RCOutput::dshot_update_tick(void* p)
|
||||
{
|
||||
chSysLockFromISR();
|
||||
RCOutput* rcout = (RCOutput*)p;
|
||||
|
@ -1201,7 +1201,7 @@ void RCOutput::dshot_send_groups(uint32_t time_out_us)
|
|||
#endif //#ifndef DISABLE_DSHOT
|
||||
}
|
||||
|
||||
void RCOutput::dshot_send_next_group(void* p)
|
||||
__RAMFUNC__ void RCOutput::dshot_send_next_group(void* p)
|
||||
{
|
||||
chSysLockFromISR();
|
||||
RCOutput* rcout = (RCOutput*)p;
|
||||
|
@ -1528,7 +1528,7 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
|
|||
/*
|
||||
unlock DMA channel after a dshot send completes and no return value is expected
|
||||
*/
|
||||
void RCOutput::dma_unlock(void *p)
|
||||
__RAMFUNC__ void RCOutput::dma_unlock(void *p)
|
||||
{
|
||||
chSysLockFromISR();
|
||||
pwm_group *group = (pwm_group *)p;
|
||||
|
@ -1546,7 +1546,7 @@ void RCOutput::dma_unlock(void *p)
|
|||
/*
|
||||
DMA interrupt handler. Used to mark DMA completed for DShot
|
||||
*/
|
||||
void RCOutput::dma_up_irq_callback(void *p, uint32_t flags)
|
||||
__RAMFUNC__ void RCOutput::dma_up_irq_callback(void *p, uint32_t flags)
|
||||
{
|
||||
pwm_group *group = (pwm_group *)p;
|
||||
chSysLockFromISR();
|
||||
|
|
|
@ -352,7 +352,7 @@ void RCOutput::bdshot_config_icu_dshot(stm32_tim_t* TIMx, uint8_t chan, uint8_t
|
|||
/*
|
||||
unlock DMA channel after a bi-directional dshot transaction completes
|
||||
*/
|
||||
void RCOutput::bdshot_finish_dshot_gcr_transaction(void *p)
|
||||
__RAMFUNC__ void RCOutput::bdshot_finish_dshot_gcr_transaction(void *p)
|
||||
{
|
||||
pwm_group *group = (pwm_group *)p;
|
||||
chSysLockFromISR();
|
||||
|
@ -456,7 +456,7 @@ uint8_t RCOutput::bdshot_find_next_ic_channel(const pwm_group& group)
|
|||
/*
|
||||
DMA UP channel interrupt handler. Used to mark DMA send completed for DShot
|
||||
*/
|
||||
void RCOutput::dma_up_irq_callback(void *p, uint32_t flags)
|
||||
__RAMFUNC__ void RCOutput::dma_up_irq_callback(void *p, uint32_t flags)
|
||||
{
|
||||
pwm_group *group = (pwm_group *)p;
|
||||
chSysLockFromISR();
|
||||
|
@ -496,7 +496,7 @@ void RCOutput::dma_up_irq_callback(void *p, uint32_t flags)
|
|||
}
|
||||
|
||||
// DMA IC channel handler. Used to mark DMA receive completed for DShot
|
||||
void RCOutput::bdshot_dma_ic_irq_callback(void *p, uint32_t flags)
|
||||
__RAMFUNC__ void RCOutput::bdshot_dma_ic_irq_callback(void *p, uint32_t flags)
|
||||
{
|
||||
chSysLockFromISR();
|
||||
|
||||
|
|
|
@ -39,6 +39,7 @@
|
|||
#include "hwdef/common/watchdog.h"
|
||||
#include <AP_Filesystem/AP_Filesystem.h>
|
||||
#include "shared_dma.h"
|
||||
#include <AP_Common/ExpandingString.h>
|
||||
|
||||
#if HAL_WITH_IO_MCU
|
||||
#include <AP_IOMCU/AP_IOMCU.h>
|
||||
|
|
|
@ -442,6 +442,12 @@ bool Storage::_flash_erase_ok(void)
|
|||
*/
|
||||
bool Storage::healthy(void)
|
||||
{
|
||||
#ifdef USE_POSIX
|
||||
// SD card storage is really slow
|
||||
if (_initialisedType == StorageBackend::SDCard) {
|
||||
return log_fd != -1 || AP_HAL::millis() - _last_empty_ms < 30000U;
|
||||
}
|
||||
#endif
|
||||
return ((_initialisedType != StorageBackend::None) &&
|
||||
(AP_HAL::millis() - _last_empty_ms < 2000u));
|
||||
}
|
||||
|
|
|
@ -29,7 +29,13 @@
|
|||
|
||||
// when using flash storage we use a small line size to make storage
|
||||
// compact and minimise the number of erase cycles needed
|
||||
#ifdef STORAGE_FLASH_PAGE
|
||||
#define CH_STORAGE_LINE_SHIFT 3
|
||||
#elif defined(USE_POSIX)
|
||||
#define CH_STORAGE_LINE_SHIFT 9
|
||||
#else
|
||||
#define CH_STORAGE_LINE_SHIFT 3
|
||||
#endif
|
||||
|
||||
#define CH_STORAGE_LINE_SIZE (1<<CH_STORAGE_LINE_SHIFT)
|
||||
#define CH_STORAGE_NUM_LINES (CH_STORAGE_SIZE/CH_STORAGE_LINE_SIZE)
|
||||
|
|
|
@ -549,7 +549,7 @@ void UARTDriver::rx_irq_cb(void* self)
|
|||
/*
|
||||
handle a RX DMA full interrupt
|
||||
*/
|
||||
void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
|
||||
__RAMFUNC__ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
|
||||
{
|
||||
#if HAL_USE_SERIAL == TRUE
|
||||
UARTDriver* uart_drv = (UARTDriver*)self;
|
||||
|
@ -895,7 +895,7 @@ bool UARTDriver::wait_timeout(uint16_t n, uint32_t timeout_ms)
|
|||
/*
|
||||
DMA transmit completion interrupt handler
|
||||
*/
|
||||
void UARTDriver::tx_complete(void* self, uint32_t flags)
|
||||
__RAMFUNC__ void UARTDriver::tx_complete(void* self, uint32_t flags)
|
||||
{
|
||||
UARTDriver* uart_drv = (UARTDriver*)self;
|
||||
chSysLockFromISR();
|
||||
|
@ -1419,7 +1419,7 @@ void UARTDriver::set_flow_control(enum flow_control flowcontrol)
|
|||
software update of rts line. We don't use the HW support for RTS as
|
||||
it has no hysteresis, so it ends up toggling RTS on every byte
|
||||
*/
|
||||
void UARTDriver::update_rts_line(void)
|
||||
__RAMFUNC__ void UARTDriver::update_rts_line(void)
|
||||
{
|
||||
if (arts_line == 0 || _flow_control == FLOW_CONTROL_DISABLE) {
|
||||
return;
|
||||
|
@ -1546,7 +1546,7 @@ void UARTDriver::set_stop_bits(int n)
|
|||
|
||||
|
||||
// record timestamp of new incoming data
|
||||
void UARTDriver::receive_timestamp_update(void)
|
||||
__RAMFUNC__ void UARTDriver::receive_timestamp_update(void)
|
||||
{
|
||||
_receive_timestamp[_receive_timestamp_idx^1] = AP_HAL::micros64();
|
||||
_receive_timestamp_idx ^= 1;
|
||||
|
|
|
@ -376,7 +376,7 @@ bool Util::was_watchdog_reset() const
|
|||
/*
|
||||
display stack usage as text buffer for @SYS/threads.txt
|
||||
*/
|
||||
void Util::thread_info(ExpandingString &str)
|
||||
__RAMFUNC__ void Util::thread_info(ExpandingString &str)
|
||||
{
|
||||
#if HAL_ENABLE_THREAD_STATISTICS
|
||||
uint64_t cumulative_cycles = ch.kernel_stats.m_crit_isr.cumulative;
|
||||
|
|
|
@ -0,0 +1,60 @@
|
|||
# hw definition file for processing by chibios_pins.py
|
||||
# for DevEBox H7 hardware.
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H750xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1061
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 25000000
|
||||
|
||||
FLASH_SIZE_KB 128
|
||||
FLASH_RESERVE_START_KB 0
|
||||
FLASH_RESERVE_END_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
# 8mb external flash
|
||||
EXT_FLASH_SIZE_MB 8
|
||||
EXT_FLASH_RESERVE_START_KB 1024
|
||||
EXT_FLASH_RESERVE_END_KB 448
|
||||
|
||||
# order of UARTs (and USB). Allow bootloading on USB and telem1
|
||||
SERIAL_ORDER OTG1 USART1 UART7
|
||||
|
||||
# UART7 is debug
|
||||
PE7 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
define BOOTLOADER_DEBUG SD7
|
||||
|
||||
# QuadSPI Flash
|
||||
PD11 QUADSPI_BK1_IO0 QUADSPI1
|
||||
PD12 QUADSPI_BK1_IO1 QUADSPI1
|
||||
PE2 QUADSPI_BK1_IO2 QUADSPI1
|
||||
PD13 QUADSPI_BK1_IO3 QUADSPI1
|
||||
PB6 QUADSPI_BK1_NCS QUADSPI1
|
||||
PB2 QUADSPI_CLK QUADSPI1
|
||||
|
||||
# IFace Device Name Bus QSPI Mode Clk Freq Size (Pow2) NCS Delay
|
||||
QSPIDEV w25q QUADSPI1 MODE3 120*MHZ 23 2
|
||||
|
||||
# USART1
|
||||
PA10 USART1_RX USART1
|
||||
PA9 USART1_TX USART1
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
PA1 LED_BOOTLOADER OUTPUT LOW
|
||||
define HAL_LED_ON 0
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PA4 MPU6000_CS CS
|
|
@ -0,0 +1,137 @@
|
|||
# hw definition file for processing by chibios_pins.py
|
||||
# for DevEBox H7 hardware based on SPRacingH7 pinout
|
||||
# configured to boot from external flash
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H750xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1061
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 25000000
|
||||
|
||||
STM32_ST_USE_TIMER 2
|
||||
|
||||
# reserve 256 bytes for comms between app and bootloader
|
||||
RAM_RESERVE_START 256
|
||||
|
||||
define NO_DATAFLASH TRUE
|
||||
|
||||
FLASH_SIZE_KB 128
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
EXT_FLASH_SIZE_MB 8
|
||||
EXT_FLASH_RESERVE_START_KB 1024
|
||||
EXT_FLASH_RESERVE_END_KB 448
|
||||
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 EMPTY EMPTY UART8
|
||||
|
||||
# Buzzer - DMA timer channel use by LEDs
|
||||
PD7 BUZZER OUTPUT GPIO(80) LOW
|
||||
define HAL_BUZZER_PIN 80
|
||||
define HAL_BUZZER_ON 1
|
||||
define HAL_BUZZER_OFF 0
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# Debug
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# SPI3 MPU6500 #1
|
||||
PA15 MPU6500_1_CS CS
|
||||
PB3 SPI3_SCK SPI3
|
||||
PB4 SPI3_MISO SPI3
|
||||
PD6 SPI3_MOSI SPI3
|
||||
|
||||
# I2C1 for baro
|
||||
PB8 I2C1_SCL I2C1 PULLUP
|
||||
PB9 I2C1_SDA I2C1 PULLUP
|
||||
|
||||
PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PC0 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
PC4 RSSI_IN ADC1
|
||||
define BOARD_RSSI_ANA_PIN 0
|
||||
|
||||
# define default battery setup
|
||||
define HAL_BATT_VOLT_PIN 13
|
||||
define HAL_BATT_CURR_PIN 12
|
||||
define HAL_BATT_VOLT_SCALE 10.9
|
||||
define HAL_BATT_CURR_SCALE 28.5
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
|
||||
PC5 RSSI_ADC ADC1
|
||||
|
||||
# USART1
|
||||
PB15 USART1_RX USART1
|
||||
PB14 USART1_TX USART1
|
||||
|
||||
# USART2 (RCIN)
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2 ALT(1)
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART3
|
||||
PD9 USART3_RX USART3
|
||||
PD8 USART3_TX USART3
|
||||
|
||||
# UART4
|
||||
PD0 UART4_RX UART4
|
||||
PD1 UART4_TX UART4
|
||||
|
||||
# UART5
|
||||
PB5 UART5_RX UART5
|
||||
PB13 UART5_TX UART5
|
||||
|
||||
# UART8
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
|
||||
# SD card
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
# QuadSPI Flash
|
||||
PD11 QUADSPI_BK1_IO0 QUADSPI1
|
||||
PD12 QUADSPI_BK1_IO1 QUADSPI1
|
||||
PE2 QUADSPI_BK1_IO2 QUADSPI1
|
||||
PD13 QUADSPI_BK1_IO3 QUADSPI1
|
||||
PB6 QUADSPI_BK1_NCS QUADSPI1
|
||||
PB2 QUADSPI_CLK QUADSPI1
|
||||
|
||||
# Motors
|
||||
PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50) # M1
|
||||
PH11 TIM5_CH2 TIM5 PWM(2) GPIO(51) # M2
|
||||
PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) # M3
|
||||
PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53) # M4
|
||||
|
||||
PA1 LED0 OUTPUT LOW GPIO(90) # Blue LED
|
||||
|
||||
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
|
||||
define ALLOW_ARM_NO_COMPASS
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
|
||||
define HAL_OS_FATFS_IO 1
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
define BOARD_PWM_COUNT_DEFAULT 4
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
#define STORAGE_FLASH_PAGE 14
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
# Nucleo LED
|
||||
PB0 LED1 OUTPUT LOW
|
|
@ -25,7 +25,7 @@ FLASH_SIZE_KB 2048
|
|||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
EXTERNAL_PROG_FLASH_MB 32
|
||||
EXT_FLASH_SIZE_MB 32
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
|
|
@ -82,4 +82,4 @@ PB2 QUADSPI_CLK QUADSPI1
|
|||
|
||||
define CAN_APP_NODE_NAME "org.cubepilot.H757"
|
||||
|
||||
EXTERNAL_PROG_FLASH_MB 32
|
||||
EXT_FLASH_SIZE_MB 32
|
||||
|
|
|
@ -25,7 +25,7 @@ FLASH_SIZE_KB 2048
|
|||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
# EXTERNAL_PROG_FLASH_MB 32
|
||||
# EXT_FLASH_SIZE_MB 32
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
|
|
@ -82,4 +82,4 @@ PB2 QUADSPI_CLK QUADSPI1
|
|||
|
||||
define CAN_APP_NODE_NAME "org.cubepilot.H757"
|
||||
|
||||
# EXTERNAL_PROG_FLASH_MB 32
|
||||
# EXT_FLASH_SIZE_MB 32
|
||||
|
|
|
@ -0,0 +1,6 @@
|
|||
# setup for LEDs on chan5
|
||||
SERVO11_FUNCTION 120
|
||||
NTF_LED_TYPES 257
|
||||
|
||||
# setup SERIAL2 for RCIN
|
||||
SERIAL2_BAUD 115
|
|
@ -0,0 +1,58 @@
|
|||
# hw definition file for processing by chibios_pins.py
|
||||
# for SP/Racing Extreme H7 hardware.
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H750xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1060
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
# limited flash that can't be used
|
||||
FLASH_SIZE_KB 128
|
||||
FLASH_RESERVE_START_KB 0
|
||||
FLASH_RESERVE_END_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
# 16mb external flash
|
||||
EXT_FLASH_SIZE_MB 16
|
||||
EXT_FLASH_RESERVE_START_KB 1024
|
||||
EXT_FLASH_RESERVE_END_KB 448
|
||||
|
||||
# order of UARTs (and USB). Allow bootloading on USB and telem1
|
||||
SERIAL_ORDER OTG1 USART1
|
||||
|
||||
# USART1
|
||||
PB15 USART1_RX USART1
|
||||
PB14 USART1_TX USART1
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
PE3 LED_BOOTLOADER OUTPUT LOW # Blue LED
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# QuadSPI Flash
|
||||
PD11 QUADSPI_BK1_IO0 QUADSPI1
|
||||
PD12 QUADSPI_BK1_IO1 QUADSPI1
|
||||
PE2 QUADSPI_BK1_IO2 QUADSPI1
|
||||
PD13 QUADSPI_BK1_IO3 QUADSPI1
|
||||
PB10 QUADSPI_BK1_NCS QUADSPI1
|
||||
PB2 QUADSPI_CLK QUADSPI1
|
||||
|
||||
# IFace Device Name Bus QSPI Mode Clk Freq Size (Pow2) NCS Delay
|
||||
QSPIDEV w25q QUADSPI1 MODE3 120*MHZ 24 2
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PB12 ICM20602_2_CS CS
|
||||
PA15 ICM20602_1_CS CS
|
||||
PE11 AT7456E_CS CS
|
|
@ -0,0 +1,174 @@
|
|||
# hw definition file for processing by chibios_pins.py
|
||||
# for SP/Racing Extreme H7 hardware.
|
||||
# thanks to betaflight for pin information
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H750xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1060
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
env OPTIMIZE -O2
|
||||
|
||||
STM32_ST_USE_TIMER 2
|
||||
|
||||
# internal flash is off limits
|
||||
FLASH_SIZE_KB 128
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
EXT_FLASH_SIZE_MB 16
|
||||
EXT_FLASH_RESERVE_START_KB 1024
|
||||
EXT_FLASH_RESERVE_END_KB 448
|
||||
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 EMPTY EMPTY UART8
|
||||
|
||||
# Buzzer - DMA timer channel use by LEDs
|
||||
PD7 BUZZER OUTPUT GPIO(80) LOW
|
||||
define HAL_BUZZER_PIN 80
|
||||
define HAL_BUZZER_ON 1
|
||||
define HAL_BUZZER_OFF 0
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# Debug
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# SPI2 ICM20602 #2
|
||||
PB12 ICM20602_2_CS CS
|
||||
PD3 SPI2_SCK SPI2
|
||||
PC2 SPI2_MISO SPI2
|
||||
PC3 SPI2_MOSI SPI2
|
||||
|
||||
# SPI3 ICM20602 #1
|
||||
PA15 ICM20602_1_CS CS
|
||||
PB3 SPI3_SCK SPI3
|
||||
PB4 SPI3_MISO SPI3
|
||||
PD6 SPI3_MOSI SPI3
|
||||
|
||||
# SPI4 for OSD
|
||||
PE11 AT7456E_CS CS
|
||||
PE12 SPI4_SCK SPI4
|
||||
PE13 SPI4_MISO SPI4
|
||||
PE14 SPI4_MOSI SPI4
|
||||
|
||||
# I2C1 for baro
|
||||
PB8 I2C1_SCL I2C1 PULLUP
|
||||
PB9 I2C1_SDA I2C1 PULLUP
|
||||
|
||||
PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PC0 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
PC4 RSSI_IN ADC1
|
||||
define BOARD_RSSI_ANA_PIN 0
|
||||
|
||||
# define default battery setup
|
||||
define HAL_BATT_VOLT_PIN 13
|
||||
define HAL_BATT_CURR_PIN 12
|
||||
define HAL_BATT_VOLT_SCALE 10.9
|
||||
define HAL_BATT_CURR_SCALE 28.5
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
|
||||
PC5 RSSI_ADC ADC1
|
||||
|
||||
# USART1
|
||||
PB15 USART1_RX USART1
|
||||
PB14 USART1_TX USART1
|
||||
|
||||
# USART2 (RCIN)
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2 ALT(1)
|
||||
define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART3
|
||||
PD9 USART3_RX USART3
|
||||
PD8 USART3_TX USART3
|
||||
|
||||
# UART4
|
||||
PD0 UART4_RX UART4
|
||||
PD1 UART4_TX UART4
|
||||
|
||||
# UART5
|
||||
PB5 UART5_RX UART5
|
||||
PB13 UART5_TX UART5
|
||||
|
||||
# UART8
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
|
||||
# SD card
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
# QuadSPI Flash
|
||||
PD11 QUADSPI_BK1_IO0 QUADSPI1
|
||||
PD12 QUADSPI_BK1_IO1 QUADSPI1
|
||||
PE2 QUADSPI_BK1_IO2 QUADSPI1
|
||||
PD13 QUADSPI_BK1_IO3 QUADSPI1
|
||||
PB10 QUADSPI_BK1_NCS QUADSPI1
|
||||
PB2 QUADSPI_CLK QUADSPI1
|
||||
|
||||
# Motors
|
||||
PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50) BIDIR # M1
|
||||
PA1 TIM5_CH2 TIM5 PWM(2) GPIO(51) # M2
|
||||
PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR # M3
|
||||
PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53) # M4
|
||||
|
||||
PB6 TIM4_CH1 TIM4 PWM(5) GPIO(54) # M5
|
||||
PB7 TIM4_CH2 TIM4 PWM(6) GPIO(55) # M6
|
||||
|
||||
PC6 TIM8_CH1 TIM8 PWM(7) GPIO(56) # M7
|
||||
PC7 TIM8_CH2 TIM8 PWM(8) GPIO(57) # M8
|
||||
|
||||
PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) # M9
|
||||
PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) # M10
|
||||
|
||||
# NeoPixel LED strip
|
||||
PA8 TIM1_CH1 TIM1 PWM(11) GPIO(60)
|
||||
PE3 LED0 OUTPUT LOW GPIO(90) # Blue LED
|
||||
|
||||
# spi devices
|
||||
SPIDEV icm20602_1 SPI3 DEVID1 ICM20602_1_CS MODE3 2*MHZ 10*MHZ
|
||||
SPIDEV icm20602_2 SPI2 DEVID2 ICM20602_2_CS MODE3 2*MHZ 10*MHZ
|
||||
SPIDEV osd SPI4 DEVID4 AT7456E_CS MODE0 10*MHZ 10*MHZ
|
||||
|
||||
DMA_PRIORITY SPI3* SPI2* TIM5*
|
||||
|
||||
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
|
||||
define ALLOW_ARM_NO_COMPASS
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
|
||||
# two IMUs
|
||||
IMU Invensense SPI:icm20602_1 ROTATION_YAW_90
|
||||
IMU Invensense SPI:icm20602_2 ROTATION_YAW_135
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 3
|
||||
|
||||
# one BARO
|
||||
BARO BMP388 I2C:0:0x76
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
define HAL_OS_FATFS_IO 1
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
define BOARD_PWM_COUNT_DEFAULT 11
|
||||
define STM32_PWM_USE_ADVANCED TRUE
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
|
@ -171,7 +171,7 @@ static void stm32_gpio_init(void) {
|
|||
/* Enabling GPIO-related clocks, the mask comes from the
|
||||
registry header file.*/
|
||||
#if defined(STM32H7)
|
||||
#if !EXTERNAL_PROG_FLASH_MB // if we have external flash resetting GPIO might disable all comms with it
|
||||
#if !EXT_FLASH_SIZE_MB // if we have external flash resetting GPIO might disable all comms with it
|
||||
rccResetAHB4(STM32_GPIO_EN_MASK);
|
||||
#endif
|
||||
rccEnableAHB4(STM32_GPIO_EN_MASK, true);
|
||||
|
|
|
@ -19,13 +19,17 @@
|
|||
generated from hwdef.dat
|
||||
*/
|
||||
|
||||
/* RAM region to be used for fast code. */
|
||||
REGION_ALIAS("FASTCODE_RAM", ram1)
|
||||
|
||||
/* stack areas are configured to be in AXI RAM (ram1) to ensure the SSBL will load the image */
|
||||
/* RAM region to be used for Main stack. This stack accommodates the processing
|
||||
of all exceptions and interrupts*/
|
||||
REGION_ALIAS("MAIN_STACK_RAM", ram0);
|
||||
REGION_ALIAS("MAIN_STACK_RAM", ram1);
|
||||
|
||||
/* RAM region to be used for the process stack. This is the stack used by
|
||||
the main() function.*/
|
||||
REGION_ALIAS("PROCESS_STACK_RAM", ram0);
|
||||
REGION_ALIAS("PROCESS_STACK_RAM", ram1);
|
||||
|
||||
/* RAM region to be used for data segment.*/
|
||||
REGION_ALIAS("DATA_RAM", ram0);
|
||||
|
@ -40,6 +44,17 @@ __ram0_start__ = ORIGIN(ram0);
|
|||
__ram0_size__ = LENGTH(ram0);
|
||||
__ram0_end__ = __ram0_start__ + __ram0_size__;
|
||||
|
||||
/* AXI */
|
||||
__ram1_start__ = ORIGIN(ram1);
|
||||
__ram1_size__ = LENGTH(ram1);
|
||||
__ram1_end__ = __ram1_start__ + __ram1_size__;
|
||||
|
||||
/* DTCM */
|
||||
__ram2_start__ = ORIGIN(ram2);
|
||||
__ram2_size__ = LENGTH(ram2);
|
||||
__ram2_end__ = __ram2_start__ + __ram2_size__;
|
||||
|
||||
/* ITCM */
|
||||
__instram_start__ = ORIGIN(instram);
|
||||
__instram_size__ = LENGTH(instram);
|
||||
__instram_end__ = __instram_start__ + __instram_size__;
|
||||
|
@ -72,18 +87,124 @@ SECTIONS
|
|||
__fini_array_end__ = .;
|
||||
} > default_flash
|
||||
|
||||
.ramfunc : ALIGN(4) SUBALIGN(4)
|
||||
/* INSTRUCTION_RAM area is fast-access ITCM used for RAM-based code, 64k on H7 */
|
||||
.fastramfunc : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__instram_init_text__ = LOADADDR(.ramfunc);
|
||||
__instram_init_text__ = LOADADDR(.fastramfunc);
|
||||
__instram_init__ = .;
|
||||
/* ChibiOS won't boot unless these are excluded */
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
|
||||
*libch.a:*(.text .text.* .rodata .rodata.* .glue_7t .glue_7 .gcc*)
|
||||
*(.ramfunc)
|
||||
/* performance critical sections of ChibiOS */
|
||||
*libch.a:ch*.*(.text*)
|
||||
*libch.a:nvic.*(.text*)
|
||||
*libch.a:bouncebuffer.*(.text*)
|
||||
*libch.a:stm32_util.*(.text*)
|
||||
*libch.a:stm32_dma.*(.text*)
|
||||
*libch.a:memstreams.*(.text*)
|
||||
*libch.a:malloc.*(.text*)
|
||||
*libch.a:hrt.*(.text*)
|
||||
*libch.a:hal*.*(.text*)
|
||||
/* a selection of performance critical functions driven CPUInfo results */
|
||||
lib/lib*.a:Semaphores.*(.text*)
|
||||
lib/lib*.a:AP_Math.*(.text*)
|
||||
lib/lib*.a:vector3.*(.text*)
|
||||
lib/lib*.a:matrix3.*(.text*)
|
||||
/* only used on debug builds */
|
||||
*libg_nano.a:*memset*(.text*)
|
||||
*libg_nano.a:*memcpy*(.text*)
|
||||
*libm.a:*(.text*)
|
||||
/* For some reason boards won't boot if libc is in RAM, but will with debug on */
|
||||
/**libc_nano.a:*(.text* .rodata*)
|
||||
*libstdc++_nano.a:(.text* .rodata*)*/
|
||||
*(.fastramfunc)
|
||||
. = ALIGN(4);
|
||||
__instram_end__ = .;
|
||||
} > instram AT > default_flash
|
||||
|
||||
/* FLASH_RAM area is primarily used for RAM-based code and data, 256k allocation on H7 */
|
||||
.ramfunc : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram1_init_text__ = LOADADDR(.ramfunc);
|
||||
__ram1_init__ = .;
|
||||
/* ChibiOS won't boot unless these are excluded */
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
|
||||
/*libch.a:*(.text* .rodata* .glue_7t .glue_7 .gcc*)*/
|
||||
/* a selection of larger performance critical functions */
|
||||
lib/lib*.a:*Filter.*(.text* .rodata*)
|
||||
lib/lib*.a:*Filter2p.*(.text* .rodata*)
|
||||
lib/lib*.a:SPIDevice.*(.text* .rodata*)
|
||||
lib/lib*.a:Util.*(.text* .rodata*)
|
||||
lib/lib*.a:Device.*(.text* .rodata*)
|
||||
lib/lib*.a:Scheduler.*(.text* .rodata*)
|
||||
lib/lib*.a:shared_dma.*(.text* .rodata*)
|
||||
lib/lib*.a:RingBuffer.*(.text* .rodata*)
|
||||
lib/lib*.a:crc.*(.text* .rodata*)
|
||||
lib/lib*.a:matrixN.*(.text* .rodata*)
|
||||
lib/lib*.a:matrix_alg.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_NavEKF*.*(.text* .rodata*)
|
||||
lib/lib*.a:EKFGSF*.*(.text* .rodata*)
|
||||
lib/lib*.a:vector2.*(.text* .rodata*)
|
||||
lib/lib*.a:quaternion.*(.text* .rodata*)
|
||||
lib/lib*.a:polygon.*(.text* .rodata*)
|
||||
/* uncomment these to test CPUInfo in FLASH_RAM */
|
||||
/*Tools/CPUInfo/CPUInfo.*(.text* .rodata*)
|
||||
Tools/CPUInfo/EKF_Maths.*(.text* .rodata*)*/
|
||||
*(.ramfunc*)
|
||||
. = ALIGN(4);
|
||||
} > ram1 AT > default_flash
|
||||
|
||||
.ram1 (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram1_clear__ = .;
|
||||
. = ALIGN(4);
|
||||
__ram1_noinit__ = .;
|
||||
*(.ram1*)
|
||||
. = ALIGN(4);
|
||||
__ram1_free__ = .;
|
||||
} > ram1
|
||||
|
||||
/* DATA_RAM area is DTCM primarily used for RAM-based data, e.g. vtables */
|
||||
.ramdata : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram2_init_text__ = LOADADDR(.ramdata);
|
||||
__ram2_init__ = .;
|
||||
/* ChibiOS won't boot unless these are excluded */
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
|
||||
/* performance critical sections of ChibiOS */
|
||||
*libch.a:ch*.*(.rodata*)
|
||||
*libch.a:nvic.*(.rodata*)
|
||||
*libch.a:bouncebuffer.*(.rodata*)
|
||||
*libch.a:stm32_util.*(.rodata*)
|
||||
*libch.a:stm32_dma.*(.rodata*)
|
||||
*libch.a:memstreams.*(.rodata*)
|
||||
*libch.a:malloc.*(.rodata*)
|
||||
*libch.a:hrt.*(.rodata*)
|
||||
*libch.a:hal*.*(.rodata*)
|
||||
/* a selection of performance critical functions driven CPUInfo results */
|
||||
lib/lib*.a:Semaphores.*(.rodata*)
|
||||
lib/lib*.a:AP_Math.*(.rodata*)
|
||||
lib/lib*.a:vector3.*(.rodata*)
|
||||
lib/lib*.a:matrix3.*(.rodata*)
|
||||
*libm.a:*(.rodata*)
|
||||
*(.ramdata*)
|
||||
. = ALIGN(4);
|
||||
} > ram2 AT > default_flash
|
||||
|
||||
.ram2 (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram2_clear__ = .;
|
||||
. = ALIGN(4);
|
||||
__ram2_noinit__ = .;
|
||||
*(.ram2*)
|
||||
. = ALIGN(4);
|
||||
__ram2_free__ = .;
|
||||
} > ram2
|
||||
|
||||
.text : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
/* we want app_descriptor near the start of flash so a false
|
||||
|
@ -210,4 +331,13 @@ SECTIONS
|
|||
. = ORIGIN(HEAP_RAM) + LENGTH(HEAP_RAM);
|
||||
__heap_end__ = .;
|
||||
} > HEAP_RAM
|
||||
|
||||
/* The crash log uses the unused part of a flash section.*/
|
||||
.crash_log (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(32);
|
||||
__crash_log_base__ = .;
|
||||
. = ORIGIN(default_flash) + LENGTH(default_flash);
|
||||
__crash_log_end__ = .;
|
||||
} > default_flash
|
||||
}
|
||||
|
|
|
@ -420,6 +420,7 @@ size_t mem_available(void)
|
|||
return totalp;
|
||||
}
|
||||
|
||||
#if CH_CFG_USE_DYNAMIC == TRUE
|
||||
/*
|
||||
allocate a thread on any available heap
|
||||
*/
|
||||
|
@ -444,6 +445,7 @@ thread_t *thread_create_alloc(size_t size,
|
|||
}
|
||||
return NULL;
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
return heap information
|
||||
|
|
|
@ -47,6 +47,7 @@
|
|||
#define STM32H743_MCUCONF
|
||||
#define STM32H753_MCUCONF
|
||||
#define STM32H745_MCUCONF
|
||||
#define STM32H750_MCUCONF
|
||||
#define STM32H755_MCUCONF
|
||||
#define STM32H747_MCUCONF
|
||||
#define STM32H757_MCUCONF
|
||||
|
@ -312,7 +313,6 @@
|
|||
#define STM32_IRQ_FDCAN2_PRIORITY 10
|
||||
|
||||
#define STM32_IRQ_MDMA_PRIORITY 9
|
||||
|
||||
#define STM32_IRQ_QUADSPI1_PRIORITY 10
|
||||
|
||||
#define STM32_IRQ_SDMMC1_PRIORITY 9
|
||||
|
@ -349,7 +349,9 @@
|
|||
#define STM32_ADC_DUAL_MODE FALSE
|
||||
#define STM32_ADC_COMPACT_SAMPLES FALSE
|
||||
#define STM32_ADC_USE_ADC12 TRUE
|
||||
#ifndef STM32H750xx
|
||||
#define STM32_ADC_USE_ADC3 TRUE
|
||||
#endif
|
||||
#define STM32_ADC_ADC12_DMA_PRIORITY 2
|
||||
#define STM32_ADC_ADC3_DMA_PRIORITY 2
|
||||
#define STM32_ADC_ADC12_IRQ_PRIORITY 5
|
||||
|
|
|
@ -29,7 +29,7 @@ mcu = {
|
|||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 0), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -1,6 +1,6 @@
|
|||
#!/usr/bin/env python
|
||||
'''
|
||||
these tables are generated from the STM32 datasheets for the STM32H743bi
|
||||
these tables are generated from the STM32 datasheets for the STM32H757
|
||||
'''
|
||||
|
||||
# additional build information for ChibiOS
|
||||
|
@ -14,18 +14,52 @@ mcu = {
|
|||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FF1E800,
|
||||
|
||||
# DMA peripheral capabilities:
|
||||
# - can't use ITCM or DTCM for any DMA
|
||||
# - SPI1 to SPI5 can use AXI SRAM, SRAM1 to SRAM3 and SRAM4 for DMA
|
||||
# - SPI6, I2C4 and ADC3 can use SRAM4 on BDMA
|
||||
# - UARTS can use AXI SRAM, SRAM1 to SRAM3 and SRAM4 for DMA
|
||||
# - I2C1, I2C2 and I2C3 can use AXI SRAM, SRAM1 to SRAM3 and SRAM4 with DMA
|
||||
# - timers can use AXI SRAM, SRAM1 to SRAM3 and SRAM4 with DMA
|
||||
# - ADC12 can use AXI SRAM, SRAM1 to SRAM3 and SRAM4
|
||||
# - SDMMC can use AXI SRAM, SRAM1 to SRAM3 with IDMA (cannot use SRAM4)
|
||||
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable (DMA and BDMA)
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
# flags of 4 means memory can be used for SDMMC DMA
|
||||
'RAM_MAP' : [
|
||||
(0x30000000, 288, 0), # SRAM1, SRAM2, SRAM3
|
||||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x38000000, 64, 1), # SRAM4. This supports both DMA and BDMA ops
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 0), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
'INSTRUCTION_RAM' : (0x00000400, 63), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
'RAM_MAP_EXTERNAL_FLASH' : [
|
||||
# SSBL checks that stack is in this region so needs to come first
|
||||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x20000000, 64, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x24000000, 128, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x30040000, 32, 0), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
'INSTRUCTION_RAM' : (0x00000400, 63), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
'FLASH_RAM' : (0x24020000, 384), # AXI SRAM used for process stack and ram functions
|
||||
'DATA_RAM' : (0x20010000, 64), # DTCM, tightly coupled, no DMA, fast
|
||||
|
||||
# avoid a problem in the bootloader by making DTCM first. The DCache init
|
||||
# when using SRAM1 as primary memory gets a hard fault in bootloader
|
||||
# we can't use DTCM first for main firmware as some builds overflow the first segment
|
||||
'RAM_MAP_BOOTLOADER' : [
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 0), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
'EXPECTED_CLOCK' : 400000000,
|
||||
|
||||
|
|
|
@ -705,6 +705,10 @@ def get_ram_map():
|
|||
ram_map = get_mcu_config('RAM_MAP_BOOTLOADER', False)
|
||||
if ram_map is not None:
|
||||
return ram_map
|
||||
elif env_vars['EXT_FLASH_SIZE_MB']:
|
||||
ram_map = get_mcu_config('RAM_MAP_EXTERNAL_FLASH', False)
|
||||
if ram_map is not None:
|
||||
return ram_map
|
||||
return get_mcu_config('RAM_MAP', True)
|
||||
|
||||
def get_flash_pages_sizes():
|
||||
|
@ -905,21 +909,29 @@ def write_mcu_config(f):
|
|||
flash_size = get_config('FLASH_SIZE_KB', type=int)
|
||||
f.write('#define BOARD_FLASH_SIZE %u\n' % flash_size)
|
||||
env_vars['BOARD_FLASH_SIZE'] = flash_size
|
||||
f.write('#define CRT1_AREAS_NUMBER 1\n')
|
||||
|
||||
flash_reserve_start = get_config(
|
||||
'FLASH_RESERVE_START_KB', default=16, type=int)
|
||||
f.write('\n// location of loaded firmware\n')
|
||||
f.write('#define FLASH_LOAD_ADDRESS 0x%08x\n' % (0x08000000 + flash_reserve_start*1024))
|
||||
f.write('#define EXTERNAL_PROG_FLASH_MB %u\n' % get_config('EXTERNAL_PROG_FLASH_MB', default=0, type=int))
|
||||
# can be no persistent parameters if no space allocated for them
|
||||
if not args.bootloader and flash_reserve_start == 0:
|
||||
f.write('#define HAL_ENABLE_SAVE_PERSISTENT_PARAMS 0\n')
|
||||
|
||||
env_vars['EXTERNAL_PROG_FLASH_MB'] = get_config('EXTERNAL_PROG_FLASH_MB', default=0, type=int)
|
||||
f.write('#define EXT_FLASH_SIZE_MB %u\n' % get_config('EXT_FLASH_SIZE_MB', default=0, type=int))
|
||||
f.write('#define EXT_FLASH_RESERVE_START_KB %u\n' % get_config('EXT_FLASH_RESERVE_START_KB', default=0, type=int))
|
||||
f.write('#define EXT_FLASH_RESERVE_END_KB %u\n' % get_config('EXT_FLASH_RESERVE_END_KB', default=0, type=int))
|
||||
|
||||
if env_vars['EXTERNAL_PROG_FLASH_MB'] and not args.bootloader:
|
||||
env_vars['EXT_FLASH_SIZE_MB'] = get_config('EXT_FLASH_SIZE_MB', default=0, type=int)
|
||||
|
||||
if env_vars['EXT_FLASH_SIZE_MB'] and not args.bootloader:
|
||||
f.write('#define CRT1_AREAS_NUMBER 3\n')
|
||||
f.write('#define CRT1_RAMFUNC_ENABLE TRUE\n') # this will enable loading program sections to RAM
|
||||
f.write('#define __RAMFUNC__ __attribute__ ((long_call, __section__(".ramfunc")))\n')
|
||||
f.write('#define PORT_IRQ_ATTRIBUTES __RAMFUNC__\n')
|
||||
f.write('#define __FASTRAMFUNC__ __attribute__ ((__section__(".fastramfunc")))\n')
|
||||
f.write('#define __RAMFUNC__ __attribute__ ((__section__(".ramfunc")))\n')
|
||||
f.write('#define PORT_IRQ_ATTRIBUTES __FASTRAMFUNC__\n')
|
||||
else:
|
||||
f.write('#define CRT1_AREAS_NUMBER 1\n')
|
||||
f.write('#define CRT1_RAMFUNC_ENABLE FALSE\n')
|
||||
|
||||
storage_flash_page = get_storage_flash_page()
|
||||
|
@ -940,8 +952,10 @@ def write_mcu_config(f):
|
|||
env_vars['ENABLE_CRASHDUMP'] = 0
|
||||
|
||||
if args.bootloader:
|
||||
if env_vars['EXTERNAL_PROG_FLASH_MB']:
|
||||
f.write('#define APP_START_ADDRESS 0x90000000\n')
|
||||
if env_vars['EXT_FLASH_SIZE_MB']:
|
||||
f.write('\n// location of loaded firmware in external flash\n')
|
||||
f.write('#define APP_START_ADDRESS 0x%08x\n' % (0x90000000 + get_config(
|
||||
'EXT_FLASH_RESERVE_START_KB', default=0, type=int)*1024))
|
||||
f.write('#define BOOT_FROM_EXT_FLASH 1\n')
|
||||
f.write('#define FLASH_BOOTLOADER_LOAD_KB %u\n' % get_config('FLASH_BOOTLOADER_LOAD_KB', type=int))
|
||||
f.write('#define FLASH_RESERVE_END_KB %u\n' % get_config('FLASH_RESERVE_END_KB', default=0, type=int))
|
||||
|
@ -1053,7 +1067,6 @@ def write_mcu_config(f):
|
|||
#define HAL_USE_I2C FALSE
|
||||
#define HAL_USE_PWM FALSE
|
||||
#define CH_DBG_ENABLE_STACK_CHECK FALSE
|
||||
#define CH_CFG_USE_DYNAMIC FALSE
|
||||
// avoid timer and RCIN threads to save memory
|
||||
#define HAL_NO_TIMER_THREAD
|
||||
#define HAL_NO_RCOUT_THREAD
|
||||
|
@ -1074,12 +1087,13 @@ def write_mcu_config(f):
|
|||
#endif
|
||||
#define HAL_USE_RTC FALSE
|
||||
#define DISABLE_SERIAL_ESC_COMM TRUE
|
||||
#define CH_CFG_USE_DYNAMIC FALSE
|
||||
''')
|
||||
if not env_vars['EXTERNAL_PROG_FLASH_MB']:
|
||||
if not env_vars['EXT_FLASH_SIZE_MB']:
|
||||
f.write('''
|
||||
#define CH_CFG_USE_HEAP FALSE
|
||||
#define CH_CFG_USE_SEMAPHORES FALSE
|
||||
#define CH_CFG_USE_MEMCORE FALSE
|
||||
#define CH_CFG_USE_SEMAPHORES FALSE
|
||||
#define CH_CFG_USE_HEAP FALSE
|
||||
''')
|
||||
if env_vars.get('ROMFS_UNCOMPRESSED', False):
|
||||
f.write('#define HAL_ROMFS_UNCOMPRESSED\n')
|
||||
|
@ -1114,20 +1128,47 @@ def write_ldscript(fname):
|
|||
# space to reserve for storage at end of flash
|
||||
flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, type=int)
|
||||
|
||||
# space to reserve for bootloader and storage at start of external flash
|
||||
ext_flash_reserve_start = get_config(
|
||||
'EXT_FLASH_RESERVE_START_KB', default=0, type=int)
|
||||
env_vars['EXT_FLASH_RESERVE_START_KB'] = str(ext_flash_reserve_start)
|
||||
|
||||
# space to reserve for storage at end of flash
|
||||
ext_flash_reserve_end = get_config('EXT_FLASH_RESERVE_END_KB', default=0, type=int)
|
||||
|
||||
# ram layout
|
||||
ram_map = get_ram_map()
|
||||
instruction_ram = get_mcu_config('INSTRUCTION_RAM', False)
|
||||
|
||||
flash_base = 0x08000000 + flash_reserve_start * 1024
|
||||
ext_flash_base = 0x90000000
|
||||
ext_flash_base = 0x90000000 + ext_flash_reserve_start * 1024
|
||||
if instruction_ram is not None:
|
||||
instruction_ram_base = instruction_ram[0]
|
||||
instruction_ram_length = instruction_ram[1]
|
||||
|
||||
ram1_start = 0
|
||||
ram1_len = 0
|
||||
flash_ram = get_mcu_config('FLASH_RAM', False)
|
||||
if flash_ram is not None:
|
||||
ram1_start = flash_ram[0]
|
||||
ram1_len = flash_ram[1] * 1024
|
||||
|
||||
ram2_start = 0
|
||||
ram2_len = 0
|
||||
data_ram = get_mcu_config('DATA_RAM', False)
|
||||
if data_ram is not None:
|
||||
ram2_start = data_ram[0]
|
||||
ram2_len = data_ram[1] * 1024
|
||||
|
||||
# get external flash if any
|
||||
ext_flash_size = get_config('EXT_FLASH_SIZE_MB', default=0, type=int)
|
||||
|
||||
if not args.bootloader:
|
||||
flash_length = flash_size - (flash_reserve_start + flash_reserve_end)
|
||||
ext_flash_length = ext_flash_size * 1024 - (ext_flash_reserve_start + ext_flash_reserve_end)
|
||||
else:
|
||||
flash_length = min(flash_size, get_config('FLASH_BOOTLOADER_LOAD_KB', type=int))
|
||||
ext_flash_length = 0
|
||||
|
||||
env_vars['FLASH_TOTAL'] = flash_length * 1024
|
||||
|
||||
|
@ -1140,7 +1181,6 @@ def write_ldscript(fname):
|
|||
ram_reserve_start = get_ram_reserve_start()
|
||||
ram0_start += ram_reserve_start
|
||||
ram0_len -= ram_reserve_start
|
||||
ext_flash_length = get_config('EXTERNAL_PROG_FLASH_MB', default=0, type=int)
|
||||
if ext_flash_length == 0 or args.bootloader:
|
||||
env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 0
|
||||
f.write('''/* generated ldscript.ld */
|
||||
|
@ -1153,25 +1193,29 @@ MEMORY
|
|||
INCLUDE common.ld
|
||||
''' % (flash_base, flash_length, ram0_start, ram0_len))
|
||||
else:
|
||||
if ext_flash_length > 32:
|
||||
if ext_flash_size > 32:
|
||||
error("We only support 24bit addressing over external flash")
|
||||
env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 1
|
||||
f.write('''/* generated ldscript.ld */
|
||||
MEMORY
|
||||
{
|
||||
default_flash : org = 0x%08x, len = %uM
|
||||
default_flash (rx) : org = 0x%08x, len = %uK
|
||||
instram : org = 0x%08x, len = %uK
|
||||
ram0 : org = 0x%08x, len = %u
|
||||
ram1 : org = 0x%08x, len = %u
|
||||
ram2 : org = 0x%08x, len = %u
|
||||
}
|
||||
|
||||
INCLUDE common_extf.ld
|
||||
''' % (ext_flash_base, ext_flash_length,
|
||||
instruction_ram_base, instruction_ram_length,
|
||||
ram0_start, ram0_len))
|
||||
ram0_start, ram0_len,
|
||||
ram1_start, ram1_len,
|
||||
ram2_start, ram2_len))
|
||||
|
||||
def copy_common_linkerscript(outdir):
|
||||
dirpath = os.path.dirname(os.path.realpath(__file__))
|
||||
if not get_config('EXTERNAL_PROG_FLASH_MB', default=0, type=int) or args.bootloader:
|
||||
if not get_config('EXT_FLASH_SIZE_MB', default=0, type=int) or args.bootloader:
|
||||
shutil.copy(os.path.join(dirpath, "../common/common.ld"),
|
||||
os.path.join(outdir, "common.ld"))
|
||||
else:
|
||||
|
|
|
@ -197,7 +197,7 @@ void spiStopHook(SPIDriver *spip)
|
|||
{
|
||||
}
|
||||
|
||||
void spiSelectHook(SPIDriver *spip)
|
||||
__RAMFUNC__ void spiSelectHook(SPIDriver *spip)
|
||||
{
|
||||
if (sdcard_running) {
|
||||
device->get_semaphore()->take_blocking();
|
||||
|
@ -205,7 +205,7 @@ void spiSelectHook(SPIDriver *spip)
|
|||
}
|
||||
}
|
||||
|
||||
void spiUnselectHook(SPIDriver *spip)
|
||||
__RAMFUNC__ void spiUnselectHook(SPIDriver *spip)
|
||||
{
|
||||
if (sdcard_running) {
|
||||
device->set_chip_select(false);
|
||||
|
@ -220,14 +220,14 @@ void spiIgnoreHook(SPIDriver *spip, size_t n)
|
|||
}
|
||||
}
|
||||
|
||||
void spiSendHook(SPIDriver *spip, size_t n, const void *txbuf)
|
||||
__RAMFUNC__ void spiSendHook(SPIDriver *spip, size_t n, const void *txbuf)
|
||||
{
|
||||
if (sdcard_running) {
|
||||
device->transfer((const uint8_t *)txbuf, n, nullptr, 0);
|
||||
}
|
||||
}
|
||||
|
||||
void spiReceiveHook(SPIDriver *spip, size_t n, void *rxbuf)
|
||||
__RAMFUNC__ void spiReceiveHook(SPIDriver *spip, size_t n, void *rxbuf)
|
||||
{
|
||||
if (sdcard_running) {
|
||||
device->transfer(nullptr, 0, (uint8_t *)rxbuf, n);
|
||||
|
|
|
@ -272,7 +272,7 @@ void panic(const char *errormsg, ...)
|
|||
#endif
|
||||
}
|
||||
|
||||
uint32_t micros()
|
||||
__FASTRAMFUNC__ uint32_t micros()
|
||||
{
|
||||
#if CH_CFG_ST_RESOLUTION == 32 && CH_CFG_ST_FREQUENCY==1000000U
|
||||
// special case optimisation for 32 bit timers
|
||||
|
@ -293,48 +293,48 @@ uint16_t micros16()
|
|||
#endif
|
||||
}
|
||||
|
||||
uint32_t millis()
|
||||
__FASTRAMFUNC__ uint32_t millis()
|
||||
{
|
||||
return hrt_millis32();
|
||||
}
|
||||
|
||||
uint16_t millis16()
|
||||
__FASTRAMFUNC__ uint16_t millis16()
|
||||
{
|
||||
return hrt_millis32() & 0xFFFF;
|
||||
}
|
||||
|
||||
uint64_t micros64()
|
||||
__FASTRAMFUNC__ uint64_t micros64()
|
||||
{
|
||||
return hrt_micros64();
|
||||
}
|
||||
|
||||
uint64_t millis64()
|
||||
__FASTRAMFUNC__ uint64_t millis64()
|
||||
{
|
||||
return hrt_micros64() / 1000U;
|
||||
}
|
||||
|
||||
|
||||
uint32_t native_micros()
|
||||
__FASTRAMFUNC__ uint32_t native_micros()
|
||||
{
|
||||
return micros();
|
||||
}
|
||||
|
||||
uint32_t native_millis()
|
||||
__FASTRAMFUNC__ uint32_t native_millis()
|
||||
{
|
||||
return millis();
|
||||
}
|
||||
|
||||
uint16_t native_millis16()
|
||||
__FASTRAMFUNC__ uint16_t native_millis16()
|
||||
{
|
||||
return millis16();
|
||||
}
|
||||
|
||||
uint64_t native_micros64()
|
||||
__FASTRAMFUNC__ uint64_t native_micros64()
|
||||
{
|
||||
return micros64();
|
||||
}
|
||||
|
||||
uint64_t native_millis64()
|
||||
__FASTRAMFUNC__ uint64_t native_millis64()
|
||||
{
|
||||
return millis64();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue