New board: SP Racing H7 Extreme

Authored-by: igor.misic <igor.misic@rimac@automobili.hr>
This commit is contained in:
Igor Mišić 2020-08-03 21:32:58 +02:00 committed by GitHub
parent ba640acfcc
commit 7eaa48e36f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
29 changed files with 7173 additions and 2 deletions

View File

@ -0,0 +1,122 @@
px4_add_board(
PLATFORM nuttx
VENDOR spracing
MODEL h7extreme
LABEL default
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
SERIAL_PORTS
# GPS1:/dev/ttyS0
# RC:/dev/ttyS1
# TEL2:/dev/ttyS2
# TEL4:/dev/ttyS3
DRIVERS
adc
barometer # all available barometer drivers
#batt_smbus
camera_capture
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
dshot
gps
#heater
#imu # all available imu drivers
#imu/adis16448
#imu/adis16477
#imu/adis16497
#imu/bmi088
imu/mpu6000
#imu/invensense/icm20602
#imu/mpu9250
#irlock
lights/blinkm
lights/rgbled
lights/rgbled_ncp5623c
magnetometer # all available magnetometer drivers
#mkblctrl
optical_flow # all available optical flow drivers
osd
#pca9685
#power_monitor/ina226
#protocol_splitter
# pwm_input - Need to create arch/stm32 arch/stm32h7 arch/kinetis and reloacate
# all arch dependant code there
pwm_out_sim
pwm_out
#roboclaw
#tap_esc
rc_input
telemetry # all available telemetry drivers
#test_ppm
tone_alarm
# uavcan - No H7 or FD can support in UAVCAN yet
MODULES
#airspeed_selector
attitude_estimator_q
battery_status
#camera_feedback
commander
dataman
#ekf2
events
#fw_att_control
#fw_pos_control_l1
land_detector
#landing_target_estimator
load_mon
#local_position_estimator
logger
mavlink
mc_att_control
mc_hover_thrust_estimator
mc_pos_control
mc_rate_control
navigator
rc_update
#rover_pos_control
sensors
#sih
temperature_compensation
vmount
#vtol_att_control
SYSTEMCMDS
#bl_update
dmesg
dumpfile
esc_calib
hardfault_log
i2cdetect
led_control
mixer
#motor_ramp
motor_test
#mtd
nshterm
param
perf
pwm
reboot
reflect
sd_bench
#shutdown
#tests # tests and test runner
top
topic_listener
tune_control
usb_connected
ver
work_queue
EXAMPLES
#bottle_drop # OBC challenge
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
#hello
#hwtest # Hardware test
#matlab_csv_serial
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
#rover_steering_control # Rover example app
#uuv_example_app
)

View File

@ -0,0 +1,13 @@
{
"board_id": 139,
"magic": "PX4FWv1",
"description": "Firmware for the SP Racing H7 Extreme board",
"image": "",
"build_time": 0,
"summary": "SPRacing_H7Extreme",
"version": "0.1",
"image_size": 0,
"image_maxsize": 1966080,
"git_identity": "",
"board_revision": 0
}

View File

@ -0,0 +1,32 @@
#!/bin/sh
#
# SP Racing H7 EXTREME specific board defaults
#------------------------------------------------------------------------------
# system_power unavailable
param set CBRK_SUPPLY_CHK 894281
if param compare SYS_AUTOSTART 0
then
# Select the Generic 250 Racer by default
param set SYS_AUTOSTART 4050
set AUTOCNF yes
fi
set LOGGER_BUF 64
if [ $AUTOCNF = yes ]
then
# Disable safety switch by default
param set CBRK_IO_SAFETY 22027
# use the Q attitude estimator, it works w/o mag or GPS.
param set SYS_MC_EST_GROUP 3
param set ATT_ACC_COMP 0
param set ATT_W_ACC 0.4000
param set ATT_W_GYRO_BIAS 0.0000
param set SYS_HAS_MAG 0
param set DSHOT_CONFIG 600
fi

View File

@ -0,0 +1,11 @@
#!/bin/sh
#
# OmnibusF4SD specific board extras init
#------------------------------------------------------------------------------
if ! param compare OSD_ATXXXX_CFG 0
then
atxxxx start
fi

View File

@ -0,0 +1,7 @@
#!/bin/sh
#
# SP Racing H7 EXTREME specific specific board MAVLink startup script.
#------------------------------------------------------------------------------
# Start MAVLink on the USB port
mavlink start -d /dev/ttyACM0

View File

@ -0,0 +1,16 @@
#!/bin/sh
#
# SP Racing H7 EXTREME specific board sensors init
#------------------------------------------------------------------------------
adc start
# Internal SPI bus ICM-20602
mpu6000 -s -b 2 -R 11 -T 20602 start # SPI 2
#mpu6000 -s -b 3 -R 10 -T 20602 start # SPI 3
#icm20602 -s -b 2 -R 5 start # SPI 2
# Internal I2C bus
bmp388 -I start

View File

@ -0,0 +1,24 @@
#
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
config BOARD_HAS_PROBES
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
default y
---help---
This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers.
config BOARD_USE_PROBES
bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11"
default n
depends on BOARD_HAS_PROBES
---help---
Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers.
config STM32_RAMFUNCS
bool "Use stm32_board_clockconfig as ram function."
default y
select ARCH_HAVE_RAMFUNCS

View File

@ -0,0 +1,506 @@
/************************************************************************************
* nuttx-configs/spracing/h7extreme/include/board.h
*
* Copyright (C) 2016-2020 Gregory Nutt. All rights reserved.
* Authors: Igor Misic <igy1000mb@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __NUTTX_CONFIG_SPRACING_H7EXTREME_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_SPRACING_H7EXTREME_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include "board_dma_map.h"
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
#include "stm32_rcc.h"
#include "stm32_sdmmc.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* The sp racing h7 extreme board provides the following clock sources:
*
* X1: 25 MHz crystal for HSE
*
* So we have these clock source available within the STM32
*
* HSI: 64 MHz RC factory-trimmed
* HSE: 25 MHz crystal for HSE
*/
#define STM32_BOARD_XTAL 8000000ul
#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
#define STM32_LSE_FREQUENCY 32768
/* Main PLL Configuration.
*
* PLL source is HSE = 8,000,000
*
* PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN
* Subject to:
*
* 1 <= PLLM <= 63
* 4 <= PLLN <= 512
* 150 MHz <= PLL_VCOL <= 420MHz
* 192 MHz <= PLL_VCOH <= 836MHz
*
* SYSCLK = PLL_VCO / PLLP
* CPUCLK = SYSCLK / D1CPRE
* Subject to
*
* PLLP1 = {2, 4, 6, 8, ..., 128}
* PLLP2,3 = {2, 3, 4, ..., 128}
* CPUCLK <= 480 MHz
*/
#define STM32_BOARD_USEHSE
#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
*
* PLL1_VCO = (25,000,000 / 5) * 160 = 800 MHz
*
* PLL1P = PLL1_VCO/2 = 800 MHz / 2 = 400 MHz
* PLL1Q = PLL1_VCO/4 = 800 MHz / 4 = 200 MHz
* PLL1R = PLL1_VCO/8 = 800 MHz / 8 = 100 MHz
*/
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \
RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP1EN | \
RCC_PLLCFGR_DIVQ1EN | \
RCC_PLLCFGR_DIVR1EN)
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(2)
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(200)
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4)
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(2)
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 200)
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4)
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
/* PLL2 */
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \
RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP2EN | \
RCC_PLLCFGR_DIVQ2EN | \
RCC_PLLCFGR_DIVR2EN)
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4)
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(260)
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2)
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(10)
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2)
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 260)
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 10)
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
/* PLL3 */
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \
RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP3EN | \
RCC_PLLCFGR_DIVQ3EN | \
RCC_PLLCFGR_DIVR3EN)
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(2)
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(50)
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2)
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(2)
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2)
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 50)
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
/* SYSCLK = PLL1P = 400MHz
* CPUCLK = SYSCLK / 1 = 400 MHz
*/
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)
/* Configure Clock Assignments */
/* AHB clock (HCLK) is SYSCLK/2 (200 MHz max)
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 200
*/
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
/* APB1 clock (PCLK1) is HCLK/2 (100 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB2 clock (PCLK2) is HCLK/2 (50 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB3 clock (PCLK3) is HCLK/2 (50 MHz) */
#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB4 clock (PCLK4) is HCLK/4 (50 MHz) */
#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* Timer clock frequencies */
/* Timers driven from APB1 will be twice PCLK1 */
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
/* Timers driven from APB2 will be twice PCLK2 */
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY)
/* Kernel Clock Configuration
*
* Note: look at Table 54 in ST Manual
*/
/* I2C123 clock source */
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI
/* SPI123 clock source */
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL1
/* SPI45 clock source */
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_APB
/* USB 1 and 2 clock source */
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_HSI48
/* ADC 1 2 3 clock source */
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2
/* QSPI clock source */
#define STM32_RCC_D1CCIPR_QSPISEL RCC_D1CCIPR_QSPISEL_PLL2
/* FLASH wait states
*
* ------------ ---------- -----------
* Vcore MAX ACLK WAIT STATES
* ------------ ---------- -----------
* 1.15-1.26 V 70 MHz 0
* (VOS1 level) 140 MHz 1
* 210 MHz 2
* 1.05-1.15 V 55 MHz 0
* (VOS2 level) 110 MHz 1
* 165 MHz 2
* 220 MHz 3
* 0.95-1.05 V 45 MHz 0
* (VOS3 level) 90 MHz 1
* 135 MHz 2
* 180 MHz 3
* 225 MHz 4
* ------------ ---------- -----------
*/
#define BOARD_FLASH_WAITSTATES 2
/* SDMMC definitions ********************************************************/
/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
*/
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
/* LED definitions ******************************************************************/
/* The sp racing h7 extreme board has three, LED_GREEN a Green LED, LED_BLUE
* Red LED can be controlled by software.
*
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
* The following definitions are used to access individual LEDs.
*/
/* LED index values for use with board_userled() */
#define BOARD_LED1 0
#define BOARD_NLEDS 1
#define BOARD_LED_RED BOARD_LED1
/* LED bits for use with board_userled_all() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
* events as follows:
*
*
* SYMBOL Meaning LED state
* Red Green Blue
* ---------------------- -------------------------- ------ ------ ----*/
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
#define LED_IDLE 8 /* MCU is in sleep mode ON OFF OFF */
/* Alternate function pin selections ************************************************/
#define GPIO_USART1_RX GPIO_USART1_RX_1 /* PB15 */
#define GPIO_USART1_TX GPIO_USART1_TX_1 /* PB14 */
#define GPIO_USART2_RX 0 /* Not in use */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
#define GPIO_UART5_RX GPIO_UART5_RX_2 /* PB5 */
#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
/* SPI
* SPI2 is gyro 1
* SPI3 is gyro 2
* SPI4 is BARO
*/
//#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
//#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
//#define GPIO_SPI1_SCK GPIO_SPI1_SCK_3 /* PG11 */
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2 /* PC2 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_5 /* PD3 */
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1 /* PD6 */
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_1 /* PB3 */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE14 */
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE12 */
/* I2C
*
* Each I2C is associated with a U[S]ART
* hence the naming I2C2_SDA_UART4 in FMU USAGE spreadsheet
*
* The optional _GPIO configurations allow the I2C driver to manually
* reset the bus to clear stuck slaves. They match the pin configuration,
* but are normally-high GPIOs.
*
*/
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
/* SDMMC1
*
* VDD 3.3
* GND
* SDMMC1_CK PC12
* SDMMC1_CMD PD2
* SDMMC1_D0 PC8
* SDMMC1_D1 PC9
* SDMMC1_D2 PC10
* SDMMC1_D3 PC11
* GPIO_SDMMC1_NCD PG0
*/
/* USB
*
* OTG_FS_DM PA11
* OTG_FS_DP PA12
* VBUS PA9
*/
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
#if defined(CONFIG_BOARD_USE_PROBES)
# include "stm32_gpio.h"
# define PROBE_N(n) (1<<((n)-1))
# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14) /* PE14 AUX1 */
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN10) /* PA10 AUX2 */
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 AUX3 */
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) /* PE9 AUX4 */
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 FMU_CAP6 */
# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 FMU_CAP5 */
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 FMU_CAP4 */
# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN5) /* PA5 FMU_CAP3 */
# define PROBE_10 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN3) /* PB3 FMU_CAP2 */
# define PROBE_11 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN11) /* PB11 FMU_CAP1 */
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \
if ((mask)& PROBE_N(10)) { stm32_configgpio(PROBE_10); } \
if ((mask)& PROBE_N(11)) { stm32_configgpio(PROBE_11); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
#else
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)
#endif
/* QSPI configuration */
#define CONFIG_STM32H7_QUADSPI
#define CONFIG_STM32H7_QSPI_FLASH_SIZE 16777216 /* bytes */
#define CONFIG_STM32H7_QSPI_FIFO_THESHOLD 1
#define CONFIG_STM32H7_QSPI_CSHT 1 /* HIGH TIME 1 CYCLE */
#define GPIO_QSPI_CS GPIO_QUADSPI_BK1_NCS_3 /* PB10 */
#define GPIO_QSPI_IO0 GPIO_QUADSPI_BK1_IO0_3 /* PD11 */
#define GPIO_QSPI_IO1 GPIO_QUADSPI_BK1_IO1_3 /* PD12 */
#define GPIO_QSPI_IO2 GPIO_QUADSPI_BK1_IO2_1 /* PE2 */
#define GPIO_QSPI_IO3 GPIO_QUADSPI_BK1_IO3_2 /* PD13 */
#define GPIO_QSPI_SCK GPIO_QUADSPI_CLK_1 /* PB2 */
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
void stm32_boardinitialize(void);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /*__NUTTX_CONFIG_SPRACING_H7EXTREME_INCLUDE_BOARD_H */

View File

@ -0,0 +1,115 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/*
| DMA1 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 |
|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|
| Channel 0 | SPI3_RX_1 | SPDIFRX_DT | SPI3_RX_2 | SPI2_RX | SPI2_TX | SPI3_TX_1 | SPDIFRX_CS | SPI3_TX_2 |
| Channel 1 | I2C1_RX | I2C3_RX | TIM7_UP_1 | - | TIM7_UP_2 | I2C1_RX_1 | I2C1_TX | I2C1_TX_1 |
| Channel 2 | TIM4_CH1 | - | I2C4_RX | TIM4_CH2 | - | I2C4_RX | TIM4_UP | TIM4_CH3 |
| Channel 3 | - | TIM2_UP_1 | I2C3_RX_1 | - | I2C3_TX | TIM2_CH1 | TIM2_CH2 | TIM2_UP_2 |
| | | TIM2_CH3 | | | | | TIM2_CH4_1 | TIM2_CH4_2 |
| Channel 4 | UART5_RX | USART3_RX | UART4_RX | USART3_TX_1 | UART4_TX | USART2_RX | USART2_TX | UART5_TX |
| Channel 5 | UART8_TX | UART7_TX | TIM3_CH4 | UART7_RX | TIM3_CH1 | TIM3_CH2 | UART8_RX | TIM3_CH3 |
| | | | TIM3_UP | | TIM3_TRIG | | | |
| Channel 6 | TIM5_CH3 | TIM5_CH4_1 | TIM5_CH1 | TIM5_CH4_2 | TIM5_CH2 | - | TIM5_UP_2 | - |
| | TIM5_UP_1 | TIM5_TRIG_1 | | TIM5_TRIG_2 | | | | |
| Channel 7 | - | TIM6_UP | I2C2_RX | I2C2_RX_1 | USART3_TX_2 | DAC1 | DAC2 | I2C2_TX |
| Channel 8 | I2C3_TX | I2C4_RX | - | - | I2C2_TX | - | I2C4_TX | - |
| Channel 9 | - | SPI2_RX | - | - | - | - | SPI2_TX | - |
| | | | | | | | | |
| Usage | | | TIM3_UP | | | USART2_RX | TIM5_UP_2 | |
| DMA2 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 |
|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|
| Channel 0 | ADC1_1 | SAI1_A | TIM8_CH1_1 | SAI1_A_1 | ADC1_2 | SAI1_B_1 | TIM1_CH1_1 | SAI2_B_2 |
| | | | TIM8_CH2_1 | | | | TIM1_CH2_1 | |
| | | | TIM8_CH3_1 | | | | TIM1_CH3_1 | |
| Channel 1 | - | DCMI_1 | ADC2_1 | ADC2_2 | SAI1_B | SPI6_TX | SPI6_RX | DCMI_2 |
| Channel 2 | ADC3_1 | ADC3_2 | - | SPI5_RX_1 | SPI5_TX_1 | CRYP_OUT | CRYP_IN | HASH_IN |
| Channel 3 | SPI1_RX_1 | - | SPI1_RX_2 | SPI1_TX_1 | SAI2_A | SPI1_TX_2 | SAI2_B | QUADSPI |
| Channel 4 | SPI4_RX_1 | SPI4_TX_1 | USART1_RX_1 | SDMMC1_1 | - | USART1_RX_2 | SDMMC1_2 | USART1_TX |
| Channel 5 | - | USART6_RX_1 | USART6_RX_2 | SPI4_RX_2 | SPI4_TX_2 | - | USART6_TX_1 | USART6_TX_2 |
| Channel 6 | TIM1_TRIG_1 | TIM1_CH1_2 | TIM1_CH2_2 | TIM1_CH1 | TIM1_CH4 | TIM1_UP | TIM1_CH3_2 | - |
| | | | | | TIM1_TRIG_2 | | | |
| | | | | | TIM1_COM | | | |
| Channel 7 | - | TIM8_UP | TIM8_CH1_2 | TIM8_CH2_2 | TIM8_CH3_2 | SPI5_RX_2 | SPI5_TX_2 | TIM8_CH4 |
| | | | | | | | | TIM8_TRIG |
| | | | | | | | | TIM8_COM |
| Channel 8 | DSFDM1_FLT0 | DSFDM1_FLT1 | DSFDM1_FLT2 | DSFDM1_FLT3 | DSFDM1_FLT0 | DSFDM1_FLT1 | DSFDM1_FLT2 | DSFDM1_FLT3 |
| Channel 9 | JPEG_IN | JPEG_OUT | SPI4_TX | JPEG_IN | JPEG_OUT | SPI5_RX | - | - |
| Channel 10 | SAI1_B | SAI2_B | SAI2_A | - | - | - | SAI1_A | - |
| Channel 11 | SDMMC2 | - | QUADSPI | - | - | SDMMC2 | - | - |
| | | | | | | | | |
| Usage | SPI4_RX_1 | TIM8_UP | | | SPI4_TX_2 | TIM1_UP | | |
*/
#define STM32_DMA_MAP(d,s,c) ((d) << 6 | (s) << 3 | (c))
#define DMA_CHAN0 (0)
#define DMA_CHAN4 (4)
#define DMA_CHAN5 (5)
#define DMAMAP_SPI2_RX STM32_DMA_MAP(DMA1,DMA_STREAM3,DMA_CHAN0)
#define DMAMAP_SPI2_TX STM32_DMA_MAP(DMA1,DMA_STREAM4,DMA_CHAN0)
#define DMAMAP_SPI3_RX_2 STM32_DMA_MAP(DMA1,DMA_STREAM2,DMA_CHAN0)
#define DMAMAP_SPI3_TX_1 STM32_DMA_MAP(DMA1,DMA_STREAM5,DMA_CHAN0)
#define DMAMAP_SPI4_RX_1 STM32_DMA_MAP(DMA2,DMA_STREAM0,DMA_CHAN4)
#define DMAMAP_SPI4_TX_2 STM32_DMA_MAP(DMA2,DMA_STREAM4,DMA_CHAN5)
// DMA1 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
// DMAMAP_TIM5_UP_1 // DMA1, Stream 0, Channel 6 (DSHOT)
// AVAILABLE // DMA1, Stream 1
#define DMAMAP_SPI3_RX DMAMAP_SPI3_RX_2 // DMA1, Stream 2, Channel 0 (SPI sensors ICM20602 2)
// DMAMAP_SPI2_RX // DMA1, Stream 3, Channel 0 (SPI sensors ICM20602 1)
// DMAMAP_SPI2_TX // DMA1, Stream 4, Channel 0 (SPI sensors ICM20602 1)
#define DMAMAP_SPI3_TX DMAMAP_SPI3_TX_1 // DMA1, Stream 5, Channel 0 (SPI sensors ICM20602 2)
// DMAMAP_TIM4_UP // DMA1, Stream 6, Channel 2 (DSHOT)
// AVAILABLE // DMA1, Stream 7
// DMA2 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
#define DMAMAP_SPI4_RX DMAMAP_SPI4_RX_1 // DMA2, Stream 0, Channel 4 (SPI OSD)
// DMAMAP_TIM8_UP // DMA2, Stream 1, Channel 7 (DSHOT)
// AVAILABLE // DMA1, Stream 2
// AVAILABLE // DMA1, Stream 3
#define DMAMAP_SPI4_TX DMAMAP_SPI4_TX_2 // DMA2, Stream 4, Channel 5 (SPI OSD)
// AVAILABLE // DMA2, Stream 5
// AVAILABLE // DMA1, Stream 6
// AVAILABLE // DMA1, Stream 7

View File

@ -0,0 +1,230 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_OS_API is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743ZI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_ITCM=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTID=0x004b
CONFIG_CDCACM_PRODUCTSTR="PX4 SP RACING H7 EXTREME"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3162
CONFIG_CDCACM_VENDORSTR="SPRacing"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MAX_TASKS=64
CONFIG_MAX_WDOGPARMS=2
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_MULTIBLOCK_DISABLE=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_REGIONS=3
CONFIG_NFILE_DESCRIPTORS=15
CONFIG_NFILE_STREAMS=8
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARCHROMFS=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
CONFIG_NSH_DISABLE_MB=y
CONFIG_NSH_DISABLE_MH=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_PIPES=y
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_PREALLOC_TIMERS=50
CONFIG_PREALLOC_WDOGS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=294912
CONFIG_RAM_START=0x30000000
CONFIG_RAW_BINARY=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_CUSTOM_CLOCKCONFIG=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_DTCMEXCLUDE=y
CONFIG_STM32H7_DTCM_PROCFS=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_RTC=y
CONFIG_STM32H7_RTC_HSECLOCK=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=1024
CONFIG_STM32H7_SPI3=y
CONFIG_STM32H7_SPI3_DMA=y
CONFIG_STM32H7_SPI3_DMA_BUFFER=1024
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI4_DMA=y
CONFIG_STM32H7_SPI4_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_SPI_DMATHRESHOLD=8
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART5=y
CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART1=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART6=y
CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y
CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TIME_EXTENDED=y
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART5_BAUD=57600
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_SERIAL_CONSOLE=y
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2688
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y

View File

@ -0,0 +1,281 @@
/****************************************************************************
* scripts/script.ld
*
* Copyright (C) 2016, 2019, 2020 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* Igor Misic <igy1000mb@gmail.com>
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The SP Racing H7 Extreme uses an STM32H750VIT6 has 128Kb of main FLASH memory and
128 MB external NAND FLASH memory.
* The flash memory is partitioned into a User Flash memory and a System
* Flash memory. Each of these memories has two banks:
*
* 1) User Flash memory:
*
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
*
* 2) System Flash memory:
*
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
*
* 3) User option bytes for user configuration, only in Bank 1.
*
* In the STM32H743II, two different boot spaces can be selected through
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
* BOOT_ADD1 option bytes:
*
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
* ST programmed value: Flash memory at 0x0800:0000
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
* ST programmed value: System bootloader at 0x1FF0:0000
*
* The SP Racing H7 Extreme has a Swtich on board, the BOOT0 pin is at ground so by default,
* the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is
* drepresed, then the boot will be from 0x1FF0:0000
*
* The STM32H743ZI also has 1024Kb of data SRAM.
* SRAM is split up into several blocks and into three power domains:
*
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
*
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
*
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
* DTCM ports. The DTCM-RAM could be used for critical real-time
* data, such as interrupt service routines or stack / heap memory.
* Both DTCM-RAMs can be used in parallel (for load/store operations)
* thanks to the Cortex-M7 dual issue capability.
*
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
*
* This RAM is connected to ITCM 64-bit interface designed for
* execution of critical real-times routines by the CPU.
*
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
* through D1 domain AXI bus matrix
*
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
*
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
* through D2 domain AHB bus matrix
*
* 3.1) 128Kb of sram beginning at address 0x3000:0000
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
*
* sram - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
*
* 4) AHB SRAM (D3 domain) accessible by most of system masters
* through D3 domain AHB bus matrix
*
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*/
MEMORY
{
dtcm (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
sram (xrw) : ORIGIN = 0x24000000, LENGTH = 512K
sram2 (xrw) : ORIGIN = 0x30000000, LENGTH = 288K
sram3 (xrw) : ORIGIN = 0x38000000, LENGTH = 64K
itcm (xrw) : ORIGIN = 0x00000000, LENGTH = 64K
flash (xrw) : ORIGIN = 0x08000000, LENGTH = 128K
qspi (xrw) : ORIGIN = 0x90100000, LENGTH = 1536K /* FW that run in memory-mapped mode */
qspi2 (xrw) : ORIGIN = 0x90280000, LENGTH = 512K /* FW segment that will be copied to ram and itcm */
conf (xrw) : ORIGIN = 0x90f80000, LENGTH = 64K /* PX4 Config on an single 64kb erasable block. */
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
EXTERN(_bootdelay_signature)
SECTIONS
{
.itcm_code : {
_start_itcm = ABSOLUTE(.);
. = ALIGN(4);
*modules__mc_att_control.a:*(.text* .rodata*)
*modules__mc_rate_control.a:*(.text* .rodata*)
*modules__rc_update.a:*(.text* .rodata*)
*drivers__mpu6000.a:*(.text* .rodata*)
*drivers__imu__invensense__icm20602.a:*(.text* .rodata*)
*drivers__device.a:*(.text* .rodata*)
*drivers__pwm_out.a:*(.text* .rodata*)
*vehicle_acceleration.a:*(.text* .rodata*)
*vehicle_angular_velocity.a:*(.text* .rodata*)
*modules__attitude_estimator_q.a:*(.text* .rodata*)
*stm32_spi.o(.text* .rodata*)
*stm32_dma.o(.text* .rodata*)
_end_itcm = ABSOLUTE(.);
} > itcm AT > qspi2
_load_itcm = LOADADDR(.itcm_code);
.sram_code : {
_start_sram = ABSOLUTE(.);
. = ALIGN(4);
*drivers__dshot.a:*(.text* .rodata*)
*modules__mc_pos_control.a:*(.text* .rodata*)
*modules__mc_hover_thrust_estimator.a:*(.text* .rodata*)
*modules__sensors.a:*(.text* .rodata*)
*libc.a:*(.text* .rodata*)
*modules__commander.a:*(.text* .rodata*)
*modules__dataman.a:*(.text* .rodata*)
*modules__events.a:*(.text* .rodata*)
*modules__load_mon.a:*(.text* .rodata*)
*modules__logger.a:*(.text* .rodata*)
*battery_status.a:*(.text* .rodata*)
*land_detector.a:*(.text* .rodata*)
*uorb_msgs.a:*(.text* .rodata*)
*arch_spi.a:*(.text* .rodata*)
_end_sram = ABSOLUTE(.);
} > sram AT > qspi2
_load_sram = LOADADDR(.sram_code);
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.rodata .rodata.*)
*(.fixup)
*(.gnu.warning)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
/*
* This is a hack to make the newlib libm __errno() call
* use the NuttX get_errno_ptr() function.
*/
__errno = get_errno_ptr;
} > qspi
.ramfunc : {
_sramfuncs = ABSOLUTE(.);
. = ALIGN(4);
*(.ramfunc .ramfunc.*)
_eramfuncs = ABSOLUTE(.);
} > sram AT > qspi
_framfuncs = LOADADDR(.ramfunc);
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > qspi
/*
* Construction data for parameters.
*/
__param ALIGN(4): {
__param_start = ABSOLUTE(.);
KEEP(*(__param*))
__param_end = ABSOLUTE(.);
} > qspi
.ARM.extab : {
*(.ARM.extab*)
} > qspi
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > qspi
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > qspi
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -0,0 +1,253 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_OS_API is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743ZI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_STACKCHECK=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTID=0x004b
CONFIG_CDCACM_PRODUCTSTR="PX4 SP Racing H7 Extreme"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3162
CONFIG_CDCACM_VENDORSTR="Holybro"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_EXCLUDE_BLOCKS=y
CONFIG_FS_PROCFS_EXCLUDE_MOUNT=y
CONFIG_FS_PROCFS_EXCLUDE_MOUNTS=y
CONFIG_FS_PROCFS_EXCLUDE_PARTITIONS=y
CONFIG_FS_PROCFS_EXCLUDE_USAGE=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MAX_TASKS=64
CONFIG_MAX_WDOGPARMS=2
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_MULTIBLOCK_DISABLE=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_REGIONS=3
CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
CONFIG_NFILE_DESCRIPTORS=20
CONFIG_NFILE_STREAMS=8
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARCHROMFS=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
CONFIG_NSH_DISABLE_MB=y
CONFIG_NSH_DISABLE_MH=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=12
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_NXFONTS_DISABLE_16BPP=y
CONFIG_NXFONTS_DISABLE_1BPP=y
CONFIG_NXFONTS_DISABLE_24BPP=y
CONFIG_NXFONTS_DISABLE_2BPP=y
CONFIG_NXFONTS_DISABLE_32BPP=y
CONFIG_NXFONTS_DISABLE_4BPP=y
CONFIG_NXFONTS_DISABLE_8BPP=y
CONFIG_PIPES=y
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_PREALLOC_TIMERS=50
CONFIG_PREALLOC_WDOGS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1536
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_DTCMEXCLUDE=y
CONFIG_STM32H7_DTCM_PROCFS=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C2=y
CONFIG_STM32H7_I2C3=y
CONFIG_STM32H7_I2C4=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_RTC=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI5=y
CONFIG_STM32H7_SPI6=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART1=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART6=y
CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y
CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TIME_EXTENDED=y
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_DMA=y
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_DMA=y
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_DMA=y
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_DMA=y
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_DMA=y
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART6_BAUD=57600
CONFIG_USART6_DMA=y
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2624
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y

View File

@ -0,0 +1,54 @@
############################################################################
#
# Copyright (c) 2020 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
add_library(drivers_board
i2c.cpp
init.c
led.c
sdio.c
spi.cpp
timer_config.cpp
usb.c
rcc.c
qspi.c
flash_w25q128.c
)
target_link_libraries(drivers_board
PRIVATE
arch_spi
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio
px4_layer
)

View File

@ -0,0 +1,203 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
* Authors: Igor Misic <igy1000mb@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_config.h
*
* sp racing h7 extreme internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_gpio.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
#define FLASH_BASED_PARAMS
#define BOARD_USE_EXTERNAL_FLASH //Configuration and firmware are in external flash
#define BOARD_HAS_USB_VALID 1 // LTC Has No USB valid
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
#define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_ARMED_STATE_LED LED_RED
#define BOARD_OVERLOAD_LED LED_RED
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that
* can be used by the Px4 Firmware in the adc driver
*/
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
#define PX4_ADC_GPIO \
/* PC4 */ GPIO_ADC12_INP4, \
/* PC1 */ GPIO_ADC123_INP11, \
/* PC0 */ GPIO_ADC123_INP10
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_RSSI_IN_CHANNEL /* PC4 */ 4
#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC1 */ 11
#define ADC_BATTERY_CURRENT_CHANNEL /* PC0 */ 10
#define ADC_CHANNELS (1 << 4) | (1 << 10) | (1 << 11)
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (10.9f)
#define BOARD_BATTERY1_A_PER_V (17.f)
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 8
#define DIRECT_INPUT_TIMER_CHANNELS 8
/* Tone alarm output */
#define GPIO_TONE_ALARM_IDLE /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN5)
#define GPIO_TONE_ALARM_GPIO /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN5)
/* USB OTG FS
*
* PA8 OTG_FS_VBUS VBUS sensing
*/
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
/* High-resolution timer */
#define HRT_TIMER 2 /* use timer2 for the HRT */
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
#define STM32_RCC_APB1ENR STM32_RCC_APB1LENR
#define RCC_APB1ENR_TIM2EN RCC_APB1LENR_TIM2EN /* This is stupid and only applies for H7 */
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS0"
#define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_TONE_ALARM_IDLE, \
GPIO_RSSI_IN, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_NUM_IO_TIMERS 3
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {1, 2, 3, 0, 4, 5, 6, 7};
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void);
/****************************************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the board.
*
****************************************************************************************************/
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>
/****************************************************************************************************
* Progmem external flash functions:
*
* This board has custom progmem functions. It is used to save data to external flash.
*
****************************************************************************************************/
void flash_w25q128_init(void);
#include <sys/types.h>
__ramfunc__ ssize_t up_progmem_ext_getpage(size_t addr);
__ramfunc__ ssize_t up_progmem_ext_eraseblock(size_t block);
__ramfunc__ ssize_t up_progmem_ext_write(size_t addr, FAR const void *buf, size_t count);
#endif /* __ASSEMBLY__ */
__END_DECLS

View File

@ -0,0 +1,503 @@
/****************************************************************************
*
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file flash_w25q128.c
*
* Board-specific external flash W25Q128 functions.
*/
#include "board_config.h"
#include "qspi.h"
#include "up_internal.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration ********************************************************************/
#define N25Q128_SECTOR_SIZE (4*1024)
#define N25Q128_SECTOR_SHIFT (12)
#define N25Q128_SECTOR_COUNT (4096)
#define N25Q128_PAGE_SIZE (256)
#define N25Q128_PAGE_SHIFT (8)
#define W25Q_DUMMY_CYCLES_FAST_READ_QUAD 6
#define W25Q_INSTR_FAST_READ_QUAD 0xEB
#define W25Q_ADDRESS_SIZE 3 // 3 bytes -> 24 bits
#define N25QXXX_READ_STATUS 0x05 /* Read status register: *
* 0x05 | SR */
#define N25QXXX_PAGE_PROGRAM 0x02 /* Page Program: *
* 0x02 | ADDR(MS) | ADDR(MID) | *
* ADDR(LS) | data */
#define N25QXXX_WRITE_ENABLE 0x06 /* Write enable: *
* 0x06 */
#define N25QXXX_WRITE_DISABLE 0x04 /* Write disable command code: *
* 0x04 */
#define N25QXXX_SUBSECTOR_ERASE 0x20 /* Sub-sector Erase (4 kB) *
* 0x20 | ADDR(MS) | ADDR(MID) | *
* ADDR(LS) */
/* N25QXXX Registers ****************************************************************/
/* Status register bit definitions */
#define STATUS_BUSY_MASK (1 << 0) /* Bit 0: Device ready/busy status */
# define STATUS_READY (0 << 0) /* 0 = Not Busy */
# define STATUS_BUSY (1 << 0) /* 1 = Busy */
#define STATUS_WEL_MASK (1 << 1) /* Bit 1: Write enable latch status */
# define STATUS_WEL_DISABLED (0 << 1) /* 0 = Not Write Enabled */
# define STATUS_WEL_ENABLED (1 << 1) /* 1 = Write Enabled */
#define STATUS_BP_SHIFT (2) /* Bits 2-4: Block protect bits */
#define STATUS_BP_MASK (7 << STATUS_BP_SHIFT)
# define STATUS_BP_NONE (0 << STATUS_BP_SHIFT)
# define STATUS_BP_ALL (7 << STATUS_BP_SHIFT)
#define STATUS_TB_MASK (1 << 5) /* Bit 5: Top / Bottom Protect */
# define STATUS_TB_TOP (0 << 5) /* 0 = BP2-BP0 protect Top down */
# define STATUS_TB_BOTTOM (1 << 5) /* 1 = BP2-BP0 protect Bottom up */
#define STATUS_BP3_MASK (1 << 5) /* Bit 6: BP3 */
#define STATUS_SRP0_MASK (1 << 7) /* Bit 7: Status register protect 0 */
# define STATUS_SRP0_UNLOCKED (0 << 7) /* 0 = WP# no effect / PS Lock Down */
# define STATUS_SRP0_LOCKED (1 << 7) /* 1 = WP# protect / OTP Lock Down */
/************************************************************************************
* Private Types
************************************************************************************/
/* This type represents the state of the MTD device. The struct mtd_dev_s must
* appear at the beginning of the definition so that you can freely cast between
* pointers to struct mtd_dev_s and struct n25qxxx_dev_s.
*/
struct n25qxxx_dev_s {
//struct mtd_dev_s mtd; /* MTD interface */
FAR struct qspi_dev_s *qspi; /* Saved QuadSPI interface instance */
uint16_t nsectors; /* Number of erase sectors */
uint8_t sectorshift; /* Log2 of sector size */
uint8_t pageshift; /* Log2 of page size */
FAR uint8_t *cmdbuf; /* Allocated command buffer */
FAR uint8_t *readbuf; /* Allocated status read buffer */
};
/****************************************************************************
* Private Data
****************************************************************************/
struct qspi_dev_s *ptr_qspi_dev;
struct qspi_meminfo_s qspi_meminfo = {
.flags = QSPIMEM_QUADIO,
.addrlen = W25Q_ADDRESS_SIZE,
.dummies = W25Q_DUMMY_CYCLES_FAST_READ_QUAD,
.cmd = W25Q_INSTR_FAST_READ_QUAD
};
struct n25qxxx_dev_s n25qxxx_dev;
uint8_t cmdbuf[4] = {0u};
uint8_t readbuf[1] = {0u};
/************************************************************************************
* Private Functions
************************************************************************************/
__ramfunc__ int n25qxxx_command(FAR struct qspi_dev_s *qspi, uint8_t cmd);
__ramfunc__ uint8_t n25qxxx_read_status(FAR struct n25qxxx_dev_s *priv);
__ramfunc__ int n25qxxx_command_read(FAR struct qspi_dev_s *qspi, uint8_t cmd,
FAR void *buffer, size_t buflen);
__ramfunc__ void n25qxxx_write_enable(FAR struct n25qxxx_dev_s *priv);
__ramfunc__ void n25qxxx_write_disable(FAR struct n25qxxx_dev_s *priv);
__ramfunc__ int n25qxxx_write_page(struct n25qxxx_dev_s *priv, FAR const uint8_t *buffer,
off_t address, size_t buflen);
__ramfunc__ int n25qxxx_write_one_page(struct n25qxxx_dev_s *priv, struct qspi_meminfo_s *meminfo);
__ramfunc__ int n25qxxx_erase_sector(struct n25qxxx_dev_s *priv, off_t sector);
__ramfunc__ bool n25qxxx_isprotected(FAR struct n25qxxx_dev_s *priv, uint8_t status,
off_t address);
__ramfunc__ int n25qxxx_command_address(FAR struct qspi_dev_s *qspi, uint8_t cmd,
off_t addr, uint8_t addrlen);
/************************************************************************************
* Public Functions
************************************************************************************/
void flash_w25q128_init(void)
{
int qspi_interface_number = 0;
ptr_qspi_dev = stm32h7_qspi_initialize(qspi_interface_number);
n25qxxx_dev.qspi = ptr_qspi_dev;
n25qxxx_dev.cmdbuf = cmdbuf;
n25qxxx_dev.readbuf = readbuf;
n25qxxx_dev.sectorshift = N25Q128_SECTOR_SHIFT;
n25qxxx_dev.pageshift = N25Q128_PAGE_SHIFT;
n25qxxx_dev.nsectors = N25Q128_SECTOR_COUNT;
}
__ramfunc__ ssize_t up_progmem_ext_getpage(size_t addr)
{
ssize_t page_address = (addr - STM32_FMC_BANK4) / N25Q128_SECTOR_COUNT;
return page_address;
}
__ramfunc__ ssize_t up_progmem_ext_eraseblock(size_t block)
{
ssize_t size = N25Q128_SECTOR_COUNT;
irqstate_t irqstate = px4_enter_critical_section();
stm32h7_qspi_exit_memorymapped(ptr_qspi_dev);
n25qxxx_erase_sector(&n25qxxx_dev, block);
stm32h7_qspi_enter_memorymapped(ptr_qspi_dev, &qspi_meminfo, 0);
px4_leave_critical_section(irqstate);
return size;
}
__ramfunc__ ssize_t up_progmem_ext_write(size_t addr, FAR const void *buf, size_t count)
{
ssize_t ret_val = 0;
irqstate_t irqstate = px4_enter_critical_section();
stm32h7_qspi_exit_memorymapped(ptr_qspi_dev);
addr &= 0xFFFFFF;
n25qxxx_write_page(&n25qxxx_dev, buf, (off_t)addr, count);
stm32h7_qspi_enter_memorymapped(ptr_qspi_dev, &qspi_meminfo, 0);
px4_leave_critical_section(irqstate);
return ret_val;
}
/************************************************************************************
* Name: n25qxxx_command
************************************************************************************/
__ramfunc__ int n25qxxx_command(FAR struct qspi_dev_s *qspi, uint8_t cmd)
{
struct qspi_cmdinfo_s cmdinfo;
finfo("CMD: %02x\n", cmd);
cmdinfo.flags = 0;
cmdinfo.addrlen = 0;
cmdinfo.cmd = cmd;
cmdinfo.buflen = 0;
cmdinfo.addr = 0;
cmdinfo.buffer = NULL;
int rv;
rv = qspi_command(qspi, &cmdinfo);
return rv;
}
/************************************************************************************
* Name: n25qxxx_read_status
************************************************************************************/
__ramfunc__ uint8_t n25qxxx_read_status(FAR struct n25qxxx_dev_s *priv)
{
DEBUGVERIFY(n25qxxx_command_read(priv->qspi, N25QXXX_READ_STATUS,
(FAR void *)&priv->readbuf[0], 1));
return priv->readbuf[0];
}
/************************************************************************************
* Name: n25qxxx_command_read
************************************************************************************/
__ramfunc__ int n25qxxx_command_read(FAR struct qspi_dev_s *qspi, uint8_t cmd,
FAR void *buffer, size_t buflen)
{
struct qspi_cmdinfo_s cmdinfo;
finfo("CMD: %02x buflen: %lu\n", cmd, (unsigned long)buflen);
cmdinfo.flags = QSPICMD_READDATA;
cmdinfo.addrlen = 0;
cmdinfo.cmd = cmd;
cmdinfo.buflen = buflen;
cmdinfo.addr = 0;
cmdinfo.buffer = buffer;
int rv;
rv = qspi_command(qspi, &cmdinfo);
return rv;
}
/************************************************************************************
* Name: n25qxxx_write_enable
************************************************************************************/
__ramfunc__ void n25qxxx_write_enable(FAR struct n25qxxx_dev_s *priv)
{
uint8_t status;
do {
n25qxxx_command(priv->qspi, N25QXXX_WRITE_ENABLE);
status = n25qxxx_read_status(priv);
} while ((status & STATUS_WEL_MASK) != STATUS_WEL_ENABLED);
}
/************************************************************************************
* Name: n25qxxx_write_disable
************************************************************************************/
__ramfunc__ void n25qxxx_write_disable(FAR struct n25qxxx_dev_s *priv)
{
uint8_t status;
do {
n25qxxx_command(priv->qspi, N25QXXX_WRITE_DISABLE);
status = n25qxxx_read_status(priv);
} while ((status & STATUS_WEL_MASK) != STATUS_WEL_DISABLED);
}
/************************************************************************************
* Name: n25qxxx_write_page
************************************************************************************/
__ramfunc__ int n25qxxx_write_page(struct n25qxxx_dev_s *priv, FAR const uint8_t *buffer,
off_t address, size_t buflen)
{
struct qspi_meminfo_s meminfo;
unsigned int pagesize;
unsigned int npages;
unsigned int firstpagesize = 0;
int ret = OK;
unsigned int i;
finfo("address: %08lx buflen: %u\n", (unsigned long)address, (unsigned)buflen);
pagesize = (1 << priv->pageshift);
/* Set up non-varying parts of transfer description */
meminfo.flags = QSPIMEM_WRITE;
meminfo.cmd = N25QXXX_PAGE_PROGRAM;
meminfo.addrlen = 3;
meminfo.dummies = 0;
meminfo.buffer = (void *)buffer;
if (0 != (address % pagesize)) {
firstpagesize = pagesize - (address % pagesize);
}
if (buflen <= firstpagesize) {
meminfo.addr = address;
meminfo.buflen = buflen;
ret = n25qxxx_write_one_page(priv, &meminfo);
} else {
if (firstpagesize > 0) {
meminfo.addr = address;
meminfo.buflen = firstpagesize;
ret = n25qxxx_write_one_page(priv, &meminfo);
buffer += firstpagesize;
address += firstpagesize;
buflen -= firstpagesize;
}
npages = (buflen >> priv->pageshift);
meminfo.buflen = pagesize;
/* Then write each page */
for (i = 0; (i < npages) && (ret == OK); i++) {
/* Set up varying parts of the transfer description */
meminfo.addr = address;
meminfo.buffer = (void *)buffer;
ret = n25qxxx_write_one_page(priv, &meminfo);
/* Update for the next time through the loop */
buffer += pagesize;
address += pagesize;
buflen -= pagesize;
}
if ((ret == OK) && (buflen > 0)) {
meminfo.addr = address;
meminfo.buffer = (void *)buffer;
meminfo.buflen = buflen;
ret = n25qxxx_write_one_page(priv, &meminfo);
}
}
return ret;
}
__ramfunc__ int n25qxxx_write_one_page(struct n25qxxx_dev_s *priv, struct qspi_meminfo_s *meminfo)
{
int ret;
n25qxxx_write_enable(priv);
ret = qspi_memory(priv->qspi, meminfo);
n25qxxx_write_disable(priv);
if (ret < 0) {
ferr("ERROR: QSPI_MEMORY failed writing address=%06x\n",
meminfo->addr);
}
return ret;
}
/************************************************************************************
* Name: n25qxxx_erase_sector
************************************************************************************/
__ramfunc__ int n25qxxx_erase_sector(struct n25qxxx_dev_s *priv, off_t sector)
{
off_t address;
uint8_t status;
finfo("sector: %08lx\n", (unsigned long)sector);
/* Check that the flash is ready and unprotected */
status = n25qxxx_read_status(priv);
if ((status & STATUS_BUSY_MASK) != STATUS_READY) {
ferr("ERROR: Flash busy: %02x", status);
return -EBUSY;
}
/* Get the address associated with the sector */
address = (off_t)sector << priv->sectorshift;
if ((status & (STATUS_BP3_MASK | STATUS_BP_MASK)) != 0 &&
n25qxxx_isprotected(priv, status, address)) {
ferr("ERROR: Flash protected: %02x", status);
return -EACCES;
}
/* Send the sector erase command */
n25qxxx_write_enable(priv);
n25qxxx_command_address(priv->qspi, N25QXXX_SUBSECTOR_ERASE, address, 3);
/* Wait for erasure to finish */
while ((n25qxxx_read_status(priv) & STATUS_BUSY_MASK) != 0);
return OK;
}
/************************************************************************************
* Name: n25qxxx_isprotected
************************************************************************************/
__ramfunc__ bool n25qxxx_isprotected(FAR struct n25qxxx_dev_s *priv, uint8_t status,
off_t address)
{
off_t protstart;
off_t protend;
off_t protsize;
unsigned int bp;
/* The BP field is spread across non-contiguous bits */
bp = (status & STATUS_BP_MASK) >> STATUS_BP_SHIFT;
if (status & STATUS_BP3_MASK) {
bp |= 8;
}
/* the BP field is essentially the power-of-two of the number of 64k sectors,
* saturated to the device size.
*/
if (0 == bp) {
return false;
}
protsize = 0x00010000;
protsize <<= (protsize << (bp - 1));
protend = (1 << priv->sectorshift) * priv->nsectors;
if (protsize > protend) {
protsize = protend;
}
/* The final protection range then depends on if the protection region is
* configured top-down or bottom up (assuming CMP=0).
*/
if ((status & STATUS_TB_MASK) != 0) {
protstart = 0x00000000;
protend = protstart + protsize;
} else {
protstart = protend - protsize;
/* protend already computed above */
}
return (address >= protstart && address < protend);
}
/************************************************************************************
* Name: n25qxxx_command_address
************************************************************************************/
__ramfunc__ int n25qxxx_command_address(FAR struct qspi_dev_s *qspi, uint8_t cmd,
off_t addr, uint8_t addrlen)
{
struct qspi_cmdinfo_s cmdinfo;
finfo("CMD: %02x Address: %04lx addrlen=%d\n", cmd, (unsigned long)addr, addrlen);
cmdinfo.flags = QSPICMD_ADDRESS;
cmdinfo.addrlen = addrlen;
cmdinfo.cmd = cmd;
cmdinfo.buflen = 0;
cmdinfo.addr = addr;
cmdinfo.buffer = NULL;
int rv;
rv = qspi_command(qspi, &cmdinfo);
return rv;
}

View File

@ -0,0 +1,239 @@
/****************************************************************************
* arch/arm/src/stm32h7/hardware/stm32_qspi.h
*
* Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved.
* Author: dev@ziggurat29.com
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32H7_HARDWARE_STM32H7_QSPI_H
#define __ARCH_ARM_SRC_STM32H7_HARDWARE_STM32H7_QSPI_H
/****************************************************************************************
* Included Files
****************************************************************************************/
#include <nuttx/config.h>
#include <arch/stm32h7/chip.h>
#include "chip.h"
/****************************************************************************************
* Pre-processor Definitions
****************************************************************************************/
/* General Characteristics **************************************************************/
#define STM32H7_QSPI_MINBITS 8 /* Minimum word width */
#define STM32H7_QSPI_MAXBITS 32 /* Maximum word width */
/* QSPI register offsets ****************************************************************/
#define STM32_QUADSPI_CR_OFFSET 0x0000 /* Control Register */
#define STM32_QUADSPI_DCR_OFFSET 0x0004 /* Device Configuration Register */
#define STM32_QUADSPI_SR_OFFSET 0x0008 /* Status Register */
#define STM32_QUADSPI_FCR_OFFSET 0x000c /* Flag Clear Register */
#define STM32_QUADSPI_DLR_OFFSET 0x0010 /* Data Length Register */
#define STM32_QUADSPI_CCR_OFFSET 0x0014 /* Communication Configuration Register */
#define STM32_QUADSPI_AR_OFFSET 0x0018 /* Address Register */
#define STM32_QUADSPI_ABR_OFFSET 0x001c /* Alternate Bytes Register */
#define STM32_QUADSPI_DR_OFFSET 0x0020 /* Data Register */
#define STM32_QUADSPI_PSMKR_OFFSET 0x0024 /* Polling Status mask Register */
#define STM32_QUADSPI_PSMAR_OFFSET 0x0028 /* Polling Status match Register */
#define STM32_QUADSPI_PIR_OFFSET 0x002c /* Polling Interval Register */
#define STM32_QUADSPI_LPTR_OFFSET 0x0030 /* Low-Power Timeout Register */
/* QSPI register addresses **************************************************************/
#define STM32_QUADSPI_CR (STM32_QUADSPI_BASE+STM32_QUADSPI_CR_OFFSET) /* Control Register */
#define STM32_QUADSPI_DCR (STM32_QUADSPI_BASE+STM32_QUADSPI_DCR_OFFSET) /* Device Configuration Register */
#define STM32_QUADSPI_SR (STM32_QUADSPI_BASE+STM32_QUADSPI_SR_OFFSET) /* Status Register */
#define STM32_QUADSPI_FCR (STM32_QUADSPI_BASE+STM32_QUADSPI_FCR_OFFSET) /* Flag Clear Register */
#define STM32_QUADSPI_DLR (STM32_QUADSPI_BASE+STM32_QUADSPI_DLR_OFFSET) /* Data Length Register */
#define STM32_QUADSPI_CCR (STM32_QUADSPI_BASE+STM32_QUADSPI_CCR_OFFSET) /* Communication Configuration Register */
#define STM32_QUADSPI_AR (STM32_QUADSPI_BASE+STM32_QUADSPI_AR_OFFSET) /* Address Register */
#define STM32_QUADSPI_ABR (STM32_QUADSPI_BASE+STM32_QUADSPI_ABR_OFFSET) /* Alternate Bytes Register */
#define STM32_QUADSPI_DR (STM32_QUADSPI_BASE+STM32_QUADSPI_DR_OFFSET) /* Data Register */
#define STM32_QUADSPI_PSMKR (STM32_QUADSPI_BASE+STM32_QUADSPI_PSMKR_OFFSET) /* Polling Status mask Register */
#define STM32_QUADSPI_PSMAR (STM32_QUADSPI_BASE+STM32_QUADSPI_PSMAR_OFFSET) /* Polling Status match Register */
#define STM32_QUADSPI_PIR (STM32_QUADSPI_BASE+STM32_QUADSPI_PIR_OFFSET) /* Polling Interval Register */
#define STM32_QUADSPI_LPTR (STM32_QUADSPI_BASE+STM32_QUADSPI_LPTR_OFFSET) /* Low-Power Timeout Register */
/* QSPI register bit definitions ********************************************************/
/* Control Register */
#define QSPI_CR_EN (1 << 0) /* Bit 0: QSPI Enable */
#define QSPI_CR_ABORT (1 << 1) /* Bit 1: Abort request */
#define QSPI_CR_TCEN (1 << 3) /* Bit 3: Timeout counter enable */
#define QSPI_CR_SSHIFT (1 << 4) /* Bit 4: Sample shift */
#define QSPI_CR_DFM (1 << 6) /* Bit 6: DFM: Dual-flash mode */
#define QSPI_CR_FSEL (1 << 7) /* Bit 7: FSEL: Flash memory selection */
#define QSPI_CR_FTHRES_SHIFT (8) /* Bits 8-11: FIFO threshold level */
#define QSPI_CR_FTHRES_MASK (0x0f << QSPI_CR_FTHRES_SHIFT)
#define QSPI_CR_TEIE (1 << 16) /* Bit 16: Transfer error interrupt enable */
#define QSPI_CR_TCIE (1 << 17) /* Bit 17: Transfer complete interrupt enable */
#define QSPI_CR_FTIE (1 << 18) /* Bit 18: FIFO threshold interrupt enable */
#define QSPI_CR_SMIE (1 << 19) /* Bit 19: Status match interrupt enable */
#define QSPI_CR_TOIE (1 << 20) /* Bit 20: TimeOut interrupt enable */
#define QSPI_CR_APMS (1 << 22) /* Bit 22: Automatic poll mode stop */
#define QSPI_CR_PMM (1 << 23) /* Bit 23: Polling match mode */
#define QSPI_CR_PRESCALER_SHIFT (24) /* Bits 24-31: Clock prescaler */
#define QSPI_CR_PRESCALER_MASK (0xff << QSPI_CR_PRESCALER_SHIFT)
/* Device Configuration Register */
#define QSPI_DCR_CKMODE (1 << 0) /* Bit 0: Mode 0 / mode 3 */
#define QSPI_DCR_CSHT_SHIFT (8) /* Bits 8-10: Chip select high time */
#define QSPI_DCR_CSHT_MASK (0x7 << QSPI_DCR_CSHT_SHIFT)
#define QSPI_DCR_FSIZE_SHIFT (16) /* Bits 16-20: Flash memory size */
#define QSPI_DCR_FSIZE_MASK (0x1f << QSPI_DCR_FSIZE_SHIFT)
/* Status Register */
#define QSPI_SR_TEF (1 << 0) /* Bit 0: Transfer error flag */
#define QSPI_SR_TCF (1 << 1) /* Bit 1: Transfer complete flag */
#define QSPI_SR_FTF (1 << 2) /* Bit 2: FIFO threshold flag */
#define QSPI_SR_SMF (1 << 3) /* Bit 3: Status match flag */
#define QSPI_SR_TOF (1 << 4) /* Bit 4: Timeout flag */
#define QSPI_SR_BUSY (1 << 5) /* Bit 5: Busy */
#define QSPI_SR_FLEVEL_SHIFT (8) /* Bits 8-12: FIFO threshold level */
#define QSPI_SR_FLEVEL_MASK (0x1f << QSPI_SR_FLEVEL_SHIFT)
/* Flag Clear Register */
#define QSPI_FCR_CTEF (1 << 0) /* Bit 0: Clear Transfer error flag */
#define QSPI_FCR_CTCF (1 << 1) /* Bit 1: Clear Transfer complete flag */
#define QSPI_FCR_CSMF (1 << 3) /* Bit 3: Clear Status match flag */
#define QSPI_FCR_CTOF (1 << 4) /* Bit 4: Clear Timeout flag */
/* Data Length Register */
/* Communication Configuration Register */
#define CCR_IMODE_NONE 0 /* No instruction */
#define CCR_IMODE_SINGLE 1 /* Instruction on a single line */
#define CCR_IMODE_DUAL 2 /* Instruction on two lines */
#define CCR_IMODE_QUAD 3 /* Instruction on four lines */
#define CCR_ADMODE_NONE 0 /* No address */
#define CCR_ADMODE_SINGLE 1 /* Address on a single line */
#define CCR_ADMODE_DUAL 2 /* Address on two lines */
#define CCR_ADMODE_QUAD 3 /* Address on four lines */
#define CCR_ADSIZE_8 0 /* 8-bit address */
#define CCR_ADSIZE_16 1 /* 16-bit address */
#define CCR_ADSIZE_24 2 /* 24-bit address */
#define CCR_ADSIZE_32 3 /* 32-bit address */
#define CCR_ABMODE_NONE 0 /* No alternate bytes */
#define CCR_ABMODE_SINGLE 1 /* Alternate bytes on a single line */
#define CCR_ABMODE_DUAL 2 /* Alternate bytes on two lines */
#define CCR_ABMODE_QUAD 3 /* Alternate bytes on four lines */
#define CCR_ABSIZE_8 0 /* 8-bit alternate byte */
#define CCR_ABSIZE_16 1 /* 16-bit alternate bytes */
#define CCR_ABSIZE_24 2 /* 24-bit alternate bytes */
#define CCR_ABSIZE_32 3 /* 32-bit alternate bytes */
#define CCR_DMODE_NONE 0 /* No data */
#define CCR_DMODE_SINGLE 1 /* Data on a single line */
#define CCR_DMODE_DUAL 2 /* Data on two lines */
#define CCR_DMODE_QUAD 3 /* Data on four lines */
#define CCR_FMODE_INDWR 0 /* Indirect write mode */
#define CCR_FMODE_INDRD 1 /* Indirect read mode */
#define CCR_FMODE_AUTOPOLL 2 /* Automatic polling mode */
#define CCR_FMODE_MEMMAP 3 /* Memory-mapped mode */
#define QSPI_CCR_INSTRUCTION_SHIFT (0) /* Bits 0-7: Instruction */
#define QSPI_CCR_INSTRUCTION_MASK (0xff << QSPI_CCR_INSTRUCTION_SHIFT)
# define QSPI_CCR_INST(n) ((uint32_t)(n) << QSPI_CCR_INSTRUCTION_SHIFT)
#define QSPI_CCR_IMODE_SHIFT (8) /* Bits 8-9: Instruction mode */
#define QSPI_CCR_IMODE_MASK (0x3 << QSPI_CCR_IMODE_SHIFT)
# define QSPI_CCR_IMODE(n) ((uint32_t)(n) << QSPI_CCR_IMODE_SHIFT)
#define QSPI_CCR_ADMODE_SHIFT (10) /* Bits 10-11: Address mode */
#define QSPI_CCR_ADMODE_MASK (0x3 << QSPI_CCR_ADMODE_SHIFT)
# define QSPI_CCR_ADMODE(n) ((uint32_t)(n) << QSPI_CCR_ADMODE_SHIFT)
#define QSPI_CCR_ADSIZE_SHIFT (12) /* Bits 12-13: Address size */
#define QSPI_CCR_ADSIZE_MASK (0x3 << QSPI_CCR_ADSIZE_SHIFT)
# define QSPI_CCR_ADSIZE(n) ((uint32_t)(n) << QSPI_CCR_ADSIZE_SHIFT)
#define QSPI_CCR_ABMODE_SHIFT (14) /* Bits 14-15: Alternate bytes mode */
#define QSPI_CCR_ABMODE_MASK (0x3 << QSPI_CCR_ABMODE_SHIFT)
# define QSPI_CCR_ABMODE(n) ((uint32_t)(n) << QSPI_CCR_ABMODE_SHIFT)
#define QSPI_CCR_ABSIZE_SHIFT (16) /* Bits 16-17: Alternate bytes size */
#define QSPI_CCR_ABSIZE_MASK (0x3 << QSPI_CCR_ABSIZE_SHIFT)
# define QSPI_CCR_ABSIZE(n) ((uint32_t)(n) << QSPI_CCR_ABSIZE_SHIFT)
#define QSPI_CCR_DCYC_SHIFT (18) /* Bits 18-23: Number of dummy cycles */
#define QSPI_CCR_DCYC_MASK (0x1f << QSPI_CCR_DCYC_SHIFT)
# define QSPI_CCR_DCYC(n) ((uint32_t)(n) << QSPI_CCR_DCYC_SHIFT)
#define QSPI_CCR_DMODE_SHIFT (24) /* Bits 24-25: Data mode */
#define QSPI_CCR_DMODE_MASK (0x3 << QSPI_CCR_DMODE_SHIFT)
# define QSPI_CCR_DMODE(n) ((uint32_t)(n) << QSPI_CCR_DMODE_SHIFT)
#define QSPI_CCR_FMODE_SHIFT (26) /* Bits 26-27: Functional mode */
#define QSPI_CCR_FMODE_MASK (0x3 << QSPI_CCR_FMODE_SHIFT)
# define QSPI_CCR_FMODE(n) ((uint32_t)(n) << QSPI_CCR_FMODE_SHIFT)
#define QSPI_CCR_SIOO (1 << 28) /* Bit 28: Send instruction only once mode */
#define QSPI_CCR_FRCM (1 << 29) /* Bit 28: Enters Free running clock mode */
#define QSPI_CCR_DDRM (1 << 31) /* Bit 31: Double data rate mode */
/* Address Register */
/* Alternate Bytes Register */
/* Data Register */
/* Polling Status mask Register */
/* Polling Status match Register */
/* Polling Interval Register */
#define QSPI_PIR_INTERVAL_SHIFT (0) /* Bits 0-15: Polling interval */
#define QSPI_PIR_INTERVAL_MASK (0xFFff << QSPI_PIR_INTERVAL_SHIFT)
/* Low-Power Timeout Register */
#define QSPI_LPTR_TIMEOUT_SHIFT (0) /* Bits 0-15: Timeout period */
#define QSPI_LPTR_TIMEOUT_MASK (0xFFff << QSPI_PIR_INTERVAL_SHIFT)
/****************************************************************************************
* Public Types
****************************************************************************************/
/****************************************************************************************
* Public Data
****************************************************************************************/
/****************************************************************************************
* Public Functions
****************************************************************************************/
#endif /* __ARCH_ARM_SRC_STM32H7_HARDWARE_STM32H4_QSPI_H */

View File

@ -0,0 +1,38 @@
/****************************************************************************
*
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/i2c_hw_description.h>
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusInternal(1),
};

View File

@ -0,0 +1,295 @@
/****************************************************************************
*
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file init.c
*
* Board-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include "board_config.h"
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include <chip.h>
#include <stm32_uart.h>
#include <arch/board/board.h>
#include "up_internal.h"
#include <px4_arch/io_timer.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
# if defined(FLASH_BASED_PARAMS)
# include <parameters/flashparams/flashfs.h>
#endif
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/*
* Ideally we'd be able to get these from up_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
/************************************************************************************
* Name: board_peripheral_reset
*
* Description:
*
************************************************************************************/
__EXPORT void board_peripheral_reset(int ms)
{
UNUSED(ms);
}
/************************************************************************************
* Name: board_on_reset
*
* Description:
* Optionally provided function called on entry to board_system_reset
* It should perform any house keeping prior to the rest.
*
* status - 1 if resetting to boot loader
* 0 if just resetting
*
************************************************************************************/
__EXPORT void board_on_reset(int status)
{
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i)));
}
if (status >= 0) {
up_mdelay(6);
}
}
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void
stm32_boardinitialize(void)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */
stm32_spiinitialize();
/* configure USB interfaces */
stm32_usbinitialize();
/* configure external memory*/
flash_w25q128_init();
}
/****************************************************************************
* Name: board_app_initialize
*
* Description:
* Perform application specific initialization. This function is never
* called directly from application code, but only indirectly via the
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
*
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* Need hrt running before using the ADC */
px4_platform_init();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
#if 0 // serial DMA is not yet implemented in NuttX for stm32h7
/* set up the serial DMA polling */
static struct hrt_call serial_dma_call;
struct timespec ts;
/*
* Poll at 1ms intervals for received bytes that have not triggered
* a DMA event.
*/
ts.tv_sec = 0;
ts.tv_nsec = 1000000;
hrt_call_every(&serial_dma_call,
ts_to_abstime(&ts),
ts_to_abstime(&ts),
(hrt_callout)stm32_serial_dma_poll,
NULL);
#endif
/* initial LED state */
drv_led_start();
led_off(LED_RED);
if (board_hardfault_init(2, true) != 0) {
led_on(LED_RED);
}
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
if (ret != OK) {
led_on(LED_RED);
return ret;
}
#endif
up_udelay(20);
/* W25128 external flash memory:
* 0x90030000 - 0x9003FFFF -> 64KB for FlashFS
* 0x90100000 - 0x902FFFFF -> 2MB for PX4 firmware
*/
/* Page calculator for W25Q128:
* page = (address - 0x90000000)/0x1000 (sector size is 0x1000 (4096 bytes))
* examples:
* 1) address = 0x90001000, page = (0x90001000 - 0x90000000)/0x1000 = 0x1
* 2) address = 0x90200000, page = (0x90200000 - 0x90000000)/0x1000 = 0x200
* 3) address = 0x90200000, page = (0x90200100 - 0x90000000)/0x1000 = 0x201
* 4) address = 0x90f80000, page = (0x90f80000 - 0x90000000)/0x1000 = 0xF80
*/
#if defined(FLASH_BASED_PARAMS)
static sector_descriptor_t params_sector_map[] = {
{0xF80, 4096, 0x90f80000},
{0xF81, 4096, 0x90f81000},
{0xF82, 4096, 0x90f82000},
{0xF83, 4096, 0x90f83000},
{0xF84, 4096, 0x90f84000},
{0xF85, 4096, 0x90f85000},
{0xF86, 4096, 0x90f86000},
{0xF87, 4096, 0x90f87000},
{0xF88, 4096, 0x90f88000},
{0xF89, 4096, 0x90f89000},
{0xF8A, 4096, 0x90f8A000},
{0xF8B, 4096, 0x90f8B000},
{0xF8C, 4096, 0x90f8C000},
{0xF8D, 4096, 0x90f8D000},
{0xF8E, 4096, 0x90f8E000},
{0xF8F, 4096, 0x90f8F000},
{0, 0, 0},
};
/* Initialize the flashfs layer to use heap allocated memory */
int result = parameter_flashfs_init(params_sector_map, NULL, 0);
if (result != OK) {
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
led_on(LED_AMBER);
return -ENODEV;
}
#endif
return OK;
}

View File

@ -0,0 +1,218 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file px4fmu2_led.c
*
* PX4FMU LED backend.
*/
#include <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include "chip.h"
#include "stm32_gpio.h"
#include "board_config.h"
#include <nuttx/board.h>
#include <arch/board/board.h>
/*
* Ideally we'd be able to get these from up_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
__END_DECLS
#ifdef CONFIG_ARCH_LEDS
static bool nuttx_owns_leds = true;
// B R S G
// 0 1 2 3
static const uint8_t xlatpx4[] = {1, 2, 4, 0};
# define xlat(p) xlatpx4[(p)]
static uint32_t g_ledmap[] = {
GPIO_nLED_RED, // Indexed by BOARD_LED_RED
};
#else
# define xlat(p) (p)
static uint32_t g_ledmap[] = {
GPIO_nLED_RED // Indexed by LED_RED
};
#endif
__EXPORT void led_init(void)
{
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
if (g_ledmap[l] != 0) {
stm32_configgpio(g_ledmap[l]);
}
}
}
static void phy_set_led(int led, bool state)
{
/* Drive Low to switch on */
if (g_ledmap[led] != 0) {
stm32_gpiowrite(g_ledmap[led], !state);
}
}
static bool phy_get_led(int led)
{
/* If Low it is on */
if (g_ledmap[led] != 0) {
return !stm32_gpioread(g_ledmap[led]);
}
return false;
}
__EXPORT void led_on(int led)
{
phy_set_led(xlat(led), true);
}
__EXPORT void led_off(int led)
{
phy_set_led(xlat(led), false);
}
__EXPORT void led_toggle(int led)
{
phy_set_led(xlat(led), !phy_get_led(xlat(led)));
}
#ifdef CONFIG_ARCH_LEDS
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_autoled_initialize
****************************************************************************/
void board_autoled_initialize(void)
{
led_init();
}
/****************************************************************************
* Name: board_autoled_on
****************************************************************************/
void board_autoled_on(int led)
{
if (!nuttx_owns_leds) {
return;
}
switch (led) {
default:
break;
case LED_HEAPALLOCATE:
break;
case LED_IRQSENABLED:
break;
case LED_STACKCREATED:
break;
case LED_INIRQ:
break;
case LED_SIGNAL:
break;
case LED_ASSERTION:
phy_set_led(BOARD_LED_RED, true);
break;
case LED_PANIC:
phy_set_led(BOARD_LED_RED, true);
break;
case LED_IDLE : /* IDLE */
phy_set_led(BOARD_LED_RED, true);
break;
}
}
/****************************************************************************
* Name: board_autoled_off
****************************************************************************/
void board_autoled_off(int led)
{
if (!nuttx_owns_leds) {
return;
}
switch (led) {
default:
break;
case LED_SIGNAL:
break;
case LED_INIRQ:
break;
case LED_ASSERTION:
phy_set_led(BOARD_LED_RED, false);
break;
case LED_PANIC:
phy_set_led(BOARD_LED_RED, false);
break;
case LED_IDLE : /* IDLE */
phy_set_led(BOARD_LED_RED, false);
break;
}
}
#endif /* CONFIG_ARCH_LEDS */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,166 @@
/****************************************************************************
* arch/arm/src/stm32h7/stm32_qspi.h
*
* Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved.
* Author: dev@ziggurat29.com
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32_STM32H7_QSPI_H
#define __ARCH_ARM_SRC_STM32_STM32H7_QSPI_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/spi/qspi.h>
#include <stdint.h>
#include <stdbool.h>
#include "chip.h"
#ifdef CONFIG_STM32H7_QUADSPI
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Inline Functions
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Public Data
****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
#define CONFIG_STM32H7_QUADSPI_USE_RAMFUNC
#ifdef CONFIG_STM32H7_QUADSPI_USE_RAMFUNC
#define QUADSPI_RAMFUNC __ramfunc__
#else
#define QUADSPI_RAMFUNC
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/* QSPI methods */
QUADSPI_RAMFUNC int qspi_lock(struct qspi_dev_s *dev, bool lock);
QUADSPI_RAMFUNC uint32_t qspi_setfrequency(struct qspi_dev_s *dev,
uint32_t frequency);
QUADSPI_RAMFUNC void qspi_setmode(struct qspi_dev_s *dev, enum qspi_mode_e mode);
QUADSPI_RAMFUNC void qspi_setbits(struct qspi_dev_s *dev, int nbits);
QUADSPI_RAMFUNC int qspi_command(struct qspi_dev_s *dev,
struct qspi_cmdinfo_s *cmdinfo);
QUADSPI_RAMFUNC int qspi_memory(struct qspi_dev_s *dev,
struct qspi_meminfo_s *meminfo);
QUADSPI_RAMFUNC FAR void *qspi_alloc(FAR struct qspi_dev_s *dev, size_t buflen);
QUADSPI_RAMFUNC void qspi_free(FAR struct qspi_dev_s *dev, FAR void *buffer);
/****************************************************************************
* Name: stm32l4_qspi_initialize
*
* Description:
* Initialize the selected QSPI port in master mode
*
* Input Parameters:
* intf - Interface number(must be zero)
*
* Returned Value:
* Valid SPI device structure reference on success; a NULL on failure
*
****************************************************************************/
struct qspi_dev_s;
FAR struct qspi_dev_s *stm32h7_qspi_initialize(int intf);
/****************************************************************************
* Name: stm32l4_qspi_enter_memorymapped
*
* Description:
* Put the QSPI device into memory mapped mode
*
* Input Parameters:
* dev - QSPI device
* meminfo - parameters like for a memory transfer used for reading
* lpto - number of cycles to wait to automatically de-assert CS
*
* Returned Value:
* None
*
****************************************************************************/
QUADSPI_RAMFUNC void stm32h7_qspi_enter_memorymapped(struct qspi_dev_s *dev,
const struct qspi_meminfo_s *meminfo,
uint32_t lpto);
/****************************************************************************
* Name: stm32l4_qspi_exit_memorymapped
*
* Description:
* Take the QSPI device out of memory mapped mode
*
* Input Parameters:
* dev - QSPI device
*
* Returned Value:
* None
*
****************************************************************************/
QUADSPI_RAMFUNC void stm32h7_qspi_exit_memorymapped(struct qspi_dev_s *dev);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* CONFIG_STM32H7_QSPI */
#endif /* __ARCH_ARM_SRC_STM32_STM32H7_QSPI_H */

View File

@ -0,0 +1,533 @@
/****************************************************************************
*
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file rcc.c
*
* Board-specific clock config functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include "board_config.h"
#include "stm32_pwr.h"
#include "hardware/stm32_axi.h"
#include "hardware/stm32_syscfg.h"
/************************************************************************************
* Definitions
************************************************************************************/
/* Allow up to 100 milliseconds for the high speed clock to become ready.
* that is a very long delay, but if the clock does not become ready we are
* hosed anyway. Normally this is very fast, but I have seen at least one
* board that required this long, long timeout for the HSE to be ready.
*/
#define HSERDY_TIMEOUT (100 * CONFIG_BOARD_LOOPSPERMSEC)
/* Same for HSI */
#define HSIRDY_TIMEOUT HSERDY_TIMEOUT
/* HSE divisor to yield ~1MHz RTC clock */
#define HSE_DIVISOR (STM32_HSE_FREQUENCY + 500000) / 1000000
/* Voltage output scale (default to Scale 1 mode) */
#ifndef STM32_PWR_VOS_SCALE
# define STM32_PWR_VOS_SCALE PWR_D3CR_VOS_SCALE_1
#endif
#if !defined(BOARD_FLASH_PROGDELAY)
# if STM32_PWR_VOS_SCALE == PWR_D3CR_VOS_SCALE_1
# if STM32_SYSCLK_FREQUENCY <= 70000000 && BOARD_FLASH_WAITSTATES == 0
# define BOARD_FLASH_PROGDELAY 0
# elif STM32_SYSCLK_FREQUENCY <= 140000000 && BOARD_FLASH_WAITSTATES == 1
# define BOARD_FLASH_PROGDELAY 10
# elif STM32_SYSCLK_FREQUENCY <= 185000000 && BOARD_FLASH_WAITSTATES == 2
# define BOARD_FLASH_PROGDELAY 1
# elif STM32_SYSCLK_FREQUENCY <= 210000000 && BOARD_FLASH_WAITSTATES == 2
# define BOARD_FLASH_PROGDELAY 2
# elif STM32_SYSCLK_FREQUENCY <= 225000000 && BOARD_FLASH_WAITSTATES == 3
# define BOARD_FLASH_PROGDELAY 2
# else
# define BOARD_FLASH_PROGDELAY 2
# endif
# endif
#endif
/* PLL are only enabled if the P,Q or R outputs are enabled. */
#undef USE_PLL1
#if STM32_PLLCFG_PLL1CFG & (RCC_PLLCFGR_DIVP1EN | RCC_PLLCFGR_DIVQ1EN | \
RCC_PLLCFGR_DIVR1EN)
# define USE_PLL1
#endif
#undef USE_PLL2
#if STM32_PLLCFG_PLL2CFG & (RCC_PLLCFGR_DIVP2EN | RCC_PLLCFGR_DIVQ2EN | \
RCC_PLLCFGR_DIVR2EN)
# define USE_PLL2
#endif
#undef USE_PLL3
#if STM32_PLLCFG_PLL3CFG & (RCC_PLLCFGR_DIVP3EN | RCC_PLLCFGR_DIVQ3EN | \
RCC_PLLCFGR_DIVR3EN)
# define USE_PLL3
#endif
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
#if defined(CONFIG_STM32H7_CUSTOM_CLOCKCONFIG)
extern uint32_t _start_itcm;
extern uint32_t _end_itcm;
extern uint32_t _load_itcm;
extern uint32_t _start_sram;
extern uint32_t _end_sram;
extern uint32_t _load_sram;
__ramfunc__ void stm32_board_clockconfig(void)
{
volatile uint32_t regval = 0;
volatile int32_t timeout;
/* This is not the best place for copying code to ITCM and RAM.
* Since our code work to slow in External Flash, we need to copy it to ITCM and RAM.
* This currently way to do it inside board specific code.
*/
const uint32_t *src;
uint32_t *dest;
for (src = &_load_itcm, dest = &_start_itcm; dest < &_end_itcm;) {
*dest++ = *src++;
}
for (src = &_load_sram, dest = &_start_sram; dest < &_end_sram;) {
*dest++ = *src++;
}
#ifdef STM32_BOARD_USEHSI
/* Enable Internal High-Speed Clock (HSI) */
regval = getreg32(STM32_RCC_CR);
regval |= RCC_CR_HSION; /* Enable HSI */
putreg32(regval, STM32_RCC_CR);
/* Wait until the HSI is ready (or until a timeout elapsed) */
for (timeout = HSIRDY_TIMEOUT; timeout > 0; timeout--) {
/* Check if the HSIRDY flag is the set in the CR */
if ((getreg32(STM32_RCC_CR) & RCC_CR_HSIRDY) != 0) {
/* If so, then break-out with timeout > 0 */
break;
}
}
#else /* if STM32_BOARD_USEHSE */
/* Enable External High-Speed Clock (HSE) */
regval = getreg32(STM32_RCC_CR);
#ifdef STM32_HSEBYP_ENABLE /* May be defined in board.h header file */
regval |= RCC_CR_HSEBYP; /* Enable HSE clock bypass */
#else
regval &= ~RCC_CR_HSEBYP; /* Disable HSE clock bypass */
#endif
regval |= RCC_CR_HSEON; /* Enable HSE */
putreg32(regval, STM32_RCC_CR);
/* Wait until the HSE is ready (or until a timeout elapsed) */
for (timeout = HSERDY_TIMEOUT; timeout > 0; timeout--) {
/* Check if the HSERDY flag is the set in the CR */
if ((getreg32(STM32_RCC_CR) & RCC_CR_HSERDY) != 0) {
/* If so, then break-out with timeout > 0 */
break;
}
}
#endif
#define CONFIG_STM32H7_HSI48
#ifdef CONFIG_STM32H7_HSI48
/* Enable HSI48 */
regval = getreg32(STM32_RCC_CR);
regval |= RCC_CR_HSI48ON;
putreg32(regval, STM32_RCC_CR);
/* Wait until the HSI48 is ready */
while ((getreg32(STM32_RCC_CR) & RCC_CR_HSI48RDY) == 0) {
}
#endif
/* Check for a timeout. If this timeout occurs, then we are hosed. We
* have no real back-up plan, although the following logic makes it look
* as though we do.
*/
if (timeout > 0) {
/* Set the D1 domain Core prescaler and the HCLK source/divider */
regval = getreg32(STM32_RCC_D1CFGR);
regval &= ~(RCC_D1CFGR_HPRE_MASK | RCC_D1CFGR_D1CPRE_MASK);
regval |= (STM32_RCC_D1CFGR_HPRE | STM32_RCC_D1CFGR_D1CPRE);
putreg32(regval, STM32_RCC_D1CFGR);
/* Set PCLK1 */
regval = getreg32(STM32_RCC_D2CFGR);
regval &= ~RCC_D2CFGR_D2PPRE2_MASK;
regval |= STM32_RCC_D2CFGR_D2PPRE1;
putreg32(regval, STM32_RCC_D2CFGR);
/* Set PCLK2 */
regval = getreg32(STM32_RCC_D2CFGR);
regval &= ~RCC_D2CFGR_D2PPRE2_MASK;
regval |= STM32_RCC_D2CFGR_D2PPRE2;
putreg32(regval, STM32_RCC_D2CFGR);
/* Set PCLK3 */
regval = getreg32(STM32_RCC_D1CFGR);
regval &= ~RCC_D1CFGR_D1PPRE_MASK;
regval |= STM32_RCC_D1CFGR_D1PPRE;
putreg32(regval, STM32_RCC_D1CFGR);
/* Set PCLK4 */
regval = getreg32(STM32_RCC_D3CFGR);
regval &= ~RCC_D3CFGR_D3PPRE_MASK;
regval |= STM32_RCC_D3CFGR_D3PPRE;
putreg32(regval, STM32_RCC_D3CFGR);
#ifdef CONFIG_STM32H7_RTC_HSECLOCK
/* Set the RTC clock divisor */
regval = getreg32(STM32_RCC_CFGR);
regval &= ~RCC_CFGR_RTCPRE_MASK;
regval |= RCC_CFGR_RTCPRE(HSE_DIVISOR);
putreg32(regval, STM32_RCC_CFGR);
#endif
/* Configure PLL123 clock source and multipiers */
#ifdef STM32_BOARD_USEHSI
regval = (RCC_PLLCKSELR_PLLSRC_HSI |
STM32_PLLCFG_PLL1M |
STM32_PLLCFG_PLL2M |
STM32_PLLCFG_PLL3M);
#else /* if STM32_BOARD_USEHSE */
regval = (RCC_PLLCKSELR_PLLSRC_HSE |
STM32_PLLCFG_PLL1M |
STM32_PLLCFG_PLL2M |
STM32_PLLCFG_PLL3M);
#endif
putreg32(regval, STM32_RCC_PLLCKSELR);
/* Each PLL offers 3 outputs with post-dividers (PLLxP/PLLxQ/PLLxR) */
/* Configure PLL1 dividers */
regval = (STM32_PLLCFG_PLL1N |
STM32_PLLCFG_PLL1P |
STM32_PLLCFG_PLL1Q |
STM32_PLLCFG_PLL1R);
putreg32(regval, STM32_RCC_PLL1DIVR);
/* Configure PLL2 dividers */
regval = (STM32_PLLCFG_PLL2N |
STM32_PLLCFG_PLL2P |
STM32_PLLCFG_PLL2Q |
STM32_PLLCFG_PLL2R);
putreg32(regval, STM32_RCC_PLL2DIVR);
/* Configure PLL3 dividers */
regval = (STM32_PLLCFG_PLL3N |
STM32_PLLCFG_PLL3P |
STM32_PLLCFG_PLL3Q |
STM32_PLLCFG_PLL3R);
putreg32(regval, STM32_RCC_PLL3DIVR);
/* Configure PLLs */
regval = (STM32_PLLCFG_PLL1CFG |
STM32_PLLCFG_PLL2CFG |
STM32_PLLCFG_PLL3CFG);
putreg32(regval, STM32_RCC_PLLCFGR);
regval = getreg32(STM32_RCC_CR);
#if defined(USE_PLL1)
/* Enable the PLL1 */
regval |= RCC_CR_PLL1ON;
#endif
#if defined(USE_PLL2)
/* Enable the PLL2 */
regval |= RCC_CR_PLL2ON;
#endif
#if defined(USE_PLL3)
/* Enable the PLL3 */
regval |= RCC_CR_PLL3ON;
#endif
putreg32(regval, STM32_RCC_CR);
#if defined(USE_PLL1)
/* Wait until the PLL1 is ready */
while ((getreg32(STM32_RCC_CR) & RCC_CR_PLL1RDY) == 0) {
}
#endif
#if defined(USE_PLL2)
/* Wait until the PLL2 is ready */
while ((getreg32(STM32_RCC_CR) & RCC_CR_PLL2RDY) == 0) {
}
#endif
#if defined(USE_PLL3)
/* Wait until the PLL3 is ready */
while ((getreg32(STM32_RCC_CR) & RCC_CR_PLL3RDY) == 0) {
}
#endif
/* Ww must write the lower byte of the PWR_CR3 register is written once
* after POR and it shall be written before changing VOS level or ck_sys
* clock frequency. No limitation applies to the upper bytes.
*
* Programming data corresponding to an invalid combination of
* LDOEN and BYPASS bits will be ignored: data will not be written,
* the written-once mechanism will lock the register and any further
* write access will be ignored. The default supply configuration will
* be kept and the ACTVOSRDY bit in PWR control status register 1 (PWR_CSR1)
* will go on indicating invalid voltage levels.
*
* N.B. The system shall be power cycled before writing a new value.
*/
regval = getreg32(STM32_PWR_CR3);
regval |= STM32_PWR_CR3_LDOEN | STM32_PWR_CR3_LDOESCUEN;
putreg32(regval, STM32_PWR_CR3);
/* Set the voltage output scale */
regval = getreg32(STM32_PWR_D3CR);
regval &= ~STM32_PWR_D3CR_VOS_MASK;
regval |= STM32_PWR_VOS_SCALE;
putreg32(regval, STM32_PWR_D3CR);
while ((getreg32(STM32_PWR_D3CR) & STM32_PWR_D3CR_VOSRDY) == 0) {
}
/* Over-drive is needed if
* - Voltage output scale 1 mode is selected and SYSCLK frequency is
* over 400 Mhz.
*/
if ((STM32_PWR_VOS_SCALE == PWR_D3CR_VOS_SCALE_1) &&
STM32_SYSCLK_FREQUENCY > 400000000) {
/* Enable System configuration controller clock to Enable ODEN */
regval = getreg32(STM32_RCC_APB4ENR);
regval |= RCC_APB4ENR_SYSCFGEN;
putreg32(regval, STM32_RCC_APB4ENR);
/* Enable Overdrive to extend the clock frequency up to 480 Mhz. */
regval = getreg32(STM32_SYSCFG_PWRCR);
regval |= SYSCFG_PWRCR_ODEN;
putreg32(regval, STM32_SYSCFG_PWRCR);
while ((getreg32(STM32_PWR_D3CR) & STM32_PWR_D3CR_VOSRDY) == 0) {
}
}
/* Configure FLASH wait states */
regval = FLASH_ACR_WRHIGHFREQ(BOARD_FLASH_PROGDELAY) |
FLASH_ACR_LATENCY(BOARD_FLASH_WAITSTATES);
putreg32(regval, STM32_FLASH_ACR);
/* Configure new QSPI source clock */
#if defined(STM32_RCC_D1CCIPR_QSPISEL)
regval = getreg32(STM32_RCC_D1CCIPR);
regval &= ~RCC_D1CCIPR_QSPISEL_MASK;
regval |= STM32_RCC_D1CCIPR_QSPISEL;
putreg32(regval, STM32_RCC_D1CCIPR);
#endif
/* Select the PLL1P as system clock source */
regval = getreg32(STM32_RCC_CFGR);
regval &= ~RCC_CFGR_SW_MASK;
regval |= RCC_CFGR_SW_PLL1;
putreg32(regval, STM32_RCC_CFGR);
/* Wait until the PLL source is used as the system clock source */
while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) !=
RCC_CFGR_SWS_PLL1) {
}
/* Configure I2C source clock */
#if (STM32_RCC_D2CCIP2R_I2C123SRC == RCC_D2CCIP2R_I2C123SEL_HSI)
/* Enable Internal High-Speed Clock (HSI) */
regval = getreg32(STM32_RCC_CR);
regval |= RCC_CR_HSION; /* Enable HSI */
regval |= RCC_CR_HSIDIV_4; /* Set HSI to 16 MHz */
putreg32(regval, STM32_RCC_CR);
/* Wait until the HSI is ready (or until a timeout elapsed) */
for (timeout = HSIRDY_TIMEOUT; timeout > 0; timeout--) {
/* Check if the HSIRDY flag is the set in the CR */
if ((getreg32(STM32_RCC_CR) & RCC_CR_HSIRDY) != 0) {
/* If so, then break-out with timeout > 0 */
break;
}
}
#endif
#if defined(STM32_RCC_D2CCIP2R_I2C123SRC)
regval = getreg32(STM32_RCC_D2CCIP2R);
regval &= ~RCC_D2CCIP2R_I2C123SEL_MASK;
regval |= STM32_RCC_D2CCIP2R_I2C123SRC;
putreg32(regval, STM32_RCC_D2CCIP2R);
#endif
#if defined(STM32_RCC_D3CCIPR_I2C4SRC)
regval = getreg32(STM32_RCC_D3CCIPR);
regval &= ~RCC_D3CCIPR_I2C4SEL_MASK;
regval |= STM32_RCC_D3CCIPR_I2C4SRC;
putreg32(regval, STM32_RCC_D3CCIPR);
#endif
/* Configure SPI source clock */
#if defined(STM32_RCC_D2CCIP1R_SPI123SRC)
regval = getreg32(STM32_RCC_D2CCIP1R);
regval &= ~RCC_D2CCIP1R_SPI123SEL_MASK;
regval |= STM32_RCC_D2CCIP1R_SPI123SRC;
putreg32(regval, STM32_RCC_D2CCIP1R);
#endif
#if defined(STM32_RCC_D2CCIP1R_SPI45SRC)
regval = getreg32(STM32_RCC_D2CCIP1R);
regval &= ~RCC_D2CCIP1R_SPI45SEL_MASK;
regval |= STM32_RCC_D2CCIP1R_SPI45SRC;
putreg32(regval, STM32_RCC_D2CCIP1R);
#endif
#if defined(STM32_RCC_D3CCIPR_SPI6SRC)
regval = getreg32(STM32_RCC_D3CCIPR);
regval &= ~RCC_D3CCIPR_SPI6SEL_MASK;
regval |= STM32_RCC_D3CCIPR_SPI6SRC;
putreg32(regval, STM32_RCC_D3CCIPR);
#endif
/* Configure USB source clock */
#if defined(STM32_RCC_D2CCIP2R_USBSRC)
regval = getreg32(STM32_RCC_D2CCIP2R);
regval &= ~RCC_D2CCIP2R_USBSEL_MASK;
regval |= STM32_RCC_D2CCIP2R_USBSRC;
putreg32(regval, STM32_RCC_D2CCIP2R);
#endif
/* Configure ADC source clock */
#if defined(STM32_RCC_D3CCIPR_ADCSEL)
regval = getreg32(STM32_RCC_D3CCIPR);
regval &= ~RCC_D3CCIPR_ADCSEL_MASK;
regval |= STM32_RCC_D3CCIPR_ADCSEL;
putreg32(regval, STM32_RCC_D3CCIPR);
#endif
#if defined(CONFIG_STM32H7_IWDG) || defined(CONFIG_STM32H7_RTC_LSICLOCK)
/* Low speed internal clock source LSI */
stm32_rcc_enablelsi();
#endif
#if defined(CONFIG_STM32H7_RTC_LSECLOCK)
/* Low speed external clock source LSE
*
* TODO: There is another case where the LSE needs to
* be enabled: if the MCO1 pin selects LSE as source.
*/
stm32_rcc_enablelse();
#endif
}
}
#endif //#if defined(CONFIG_STM32H7_CUSTOM_CLOCKCONFIG)

View File

@ -0,0 +1,177 @@
/****************************************************************************
*
* Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include "chip.h"
#include "board_config.h"
#include "stm32_gpio.h"
#include "stm32_sdmmc.h"
#ifdef CONFIG_MMCSD
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Card detections requires card support and a card detection GPIO */
#define HAVE_NCD 1
#if !defined(GPIO_SDMMC1_NCD)
# undef HAVE_NCD
#endif
/****************************************************************************
* Private Data
****************************************************************************/
static FAR struct sdio_dev_s *sdio_dev;
#ifdef HAVE_NCD
static bool g_sd_inserted = 0xff; /* Impossible value */
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_ncd_interrupt
*
* Description:
* Card detect interrupt handler.
*
****************************************************************************/
#ifdef HAVE_NCD
static int stm32_ncd_interrupt(int irq, FAR void *context)
{
bool present;
present = !stm32_gpioread(GPIO_SDMMC1_NCD);
if (sdio_dev && present != g_sd_inserted) {
sdio_mediachange(sdio_dev, present);
g_sd_inserted = present;
}
return OK;
}
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void)
{
int ret;
#ifdef HAVE_NCD
/* Card detect */
bool cd_status;
/* Configure the card detect GPIO */
stm32_configgpio(GPIO_SDMMC1_NCD);
/* Register an interrupt handler for the card detect pin */
stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt);
#endif
/* Mount the SDIO-based MMC/SD block driver */
/* First, get an instance of the SDIO interface */
finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO);
sdio_dev = sdio_initialize(SDIO_SLOTNO);
if (!sdio_dev) {
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
return -ENODEV;
}
/* Now bind the SDIO interface to the MMC/SD driver */
finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR);
ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev);
if (ret != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
return ret;
}
finfo("Successfully bound SDIO to the MMC/SD driver\n");
#ifdef HAVE_NCD
/* Use SD card detect pin to check if a card is g_sd_inserted */
cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD);
finfo("Card detect : %d\n", cd_status);
sdio_mediachange(sdio_dev, cd_status);
#else
/* Assume that the SD card is inserted. What choice do we have? */
sdio_mediachange(sdio_dev, true);
#endif
return OK;
}
#endif /* CONFIG_MMCSD */

View File

@ -0,0 +1,51 @@
/****************************************************************************
*
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/spi_hw_description.h>
#include <drivers/drv_sensor.h>
#include <nuttx/spi/spi.h>
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortB, GPIO::Pin12}, SPI::DRDY{GPIO::PortE, GPIO::Pin15})
}),
initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin4})
}),
initSPIBus(SPI::Bus::SPI4, {
initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortE, GPIO::Pin11}),
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses);

View File

@ -0,0 +1,64 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/io_timer_hw_description.h>
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer5, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}),
initIOTimer(Timer::Timer8, DMA{DMA::Index2, DMA::Stream1, DMA::Channel7}),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}), //Motor 1
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}), //Motor 2
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}), //Motor 3
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}), //Motor 4
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortB, GPIO::Pin6}), //Motor 5
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortB, GPIO::Pin7}), //Motor 6
/*
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin6}), //Motor 9
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin7}), //Motor 10
*/
initIOTimerChannel(io_timers, {Timer::Timer8, Timer::Channel1}, {GPIO::PortC, GPIO::Pin6}), //Motor 7
initIOTimerChannel(io_timers, {Timer::Timer8, Timer::Channel2}, {GPIO::PortC, GPIO::Pin7}), //Motor 8
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
initIOTimerChannelMapping(io_timers, timer_io_channels);

View File

@ -0,0 +1,105 @@
/****************************************************************************
*
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file px4fmu_usb.c
*
* Board-specific USB functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
#include <up_arch.h>
#include <chip.h>
#include <stm32_gpio.h>
#include <stm32_otg.h>
#include "board_config.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the PX4FMU board.
*
************************************************************************************/
__EXPORT void stm32_usbinitialize(void)
{
/* The OTG FS has an internal soft pull-up */
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32H7_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif
}
/************************************************************************************
* Name: stm32_usbsuspend
*
* Description:
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
* used. This function is called whenever the USB enters or leaves suspend mode.
* This is an opportunity for the board logic to shutdown clocks, power, etc.
* while the USB is suspended.
*
************************************************************************************/
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}

View File

@ -0,0 +1,125 @@
px4_add_board(
PLATFORM nuttx
VENDOR spracing
MODEL h7extreme
LABEL stackcheck
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
#BUILD_BOOTLOADER
#IO px4_io-v2_default
TESTING
# UAVCAN_INTERFACES 2 - No H7 or FD can support in UAVCAN
SERIAL_PORTS
GPS1:/dev/ttyS0
TEL1:/dev/ttyS1
TEL2:/dev/ttyS2
TEL4:/dev/ttyS3
DRIVERS
adc
#barometer # all available barometer drivers
barometer/ms5611
batt_smbus
#camera_capture
#camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
#dshot
gps
heater
#imu # all available imu drivers
#imu/adis16448
#imu/adis16477
#imu/adis16497
#imu/bmi088
imu/mpu6000
#imu/mpu9250
#irlock
#lights/blinkm
#lights/rgbled
#lights/rgbled_ncp5623c
magnetometer # all available magnetometer drivers
#mkblctrl
#optical_flow # all available optical flow drivers
#osd
#pca9685
#power_monitor/ina226
#protocol_splitter
# pwm_input - Need to create arch/stm32 arch/stm32h7 arch/kinetis and reloacate
# all arch dependant code there
pwm_out_sim
px4fmu
#roboclaw
#tap_esc
telemetry # all available telemetry drivers
test_ppm
tone_alarm
# uavcan - No H7 or FD can support in UAVCAN yet
MODULES
airspeed_selector
#attitude_estimator_q
battery_status
#camera_feedback
commander
dataman
ekf2
events
fw_att_control
fw_pos_control_l1
land_detector
#landing_target_estimator
load_mon
#local_position_estimator
logger
mavlink
mc_att_control
mc_pos_control
mc_rate_control
navigator
rc_update
#rover_pos_control
sensors
#sih
temperature_compensation
vmount
vtol_att_control
SYSTEMCMDS
#bl_update
config
dmesg
dumpfile
esc_calib
hardfault_log
i2cdetect
led_control
mixer
motor_ramp
motor_test
#mtd
nshterm
param
perf
pwm
reboot
reflect
sd_bench
shutdown
tests # tests and test runner
top
topic_listener
tune_control
usb_connected
ver
work_queue
EXAMPLES
#bottle_drop # OBC challenge
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
#hello
#hwtest # Hardware test
#matlab_csv_serial
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
#rover_steering_control # Rover example app
#uuv_example_app
)

View File

@ -54,8 +54,9 @@
#include "flashfs.h"
#include <nuttx/compiler.h>
#include <nuttx/progmem.h>
#include <board_config.h>
#if defined(CONFIG_ARCH_HAVE_PROGMEM)
#if defined(CONFIG_ARCH_HAVE_PROGMEM) || defined(BOARD_USE_EXTERNAL_FLASH)
/****************************************************************************
* Pre-processor Definitions
@ -647,11 +648,19 @@ static sector_descriptor_t *get_sector_info(flash_entry_header_t *current)
static int erase_sector(sector_descriptor_t *sm, flash_entry_header_t *pf)
{
int rv = 0;
#if defined(BOARD_USE_EXTERNAL_FLASH)
ssize_t block = up_progmem_ext_getpage((size_t)pf);
#else
ssize_t block = up_progmem_getpage((size_t)pf);
#endif
if (block > 0 && block == sm->page) {
last_erased = sm->page;
#if defined(BOARD_USE_EXTERNAL_FLASH)
ssize_t size = up_progmem_ext_eraseblock(block);
#else
ssize_t size = up_progmem_eraseblock(block);
#endif
if (size < 0 || size != (ssize_t)sm->size) {
rv = size;
@ -681,7 +690,11 @@ static int erase_entry(flash_entry_header_t *pf)
{
h_flag_t data = ErasedEntry;
size_t size = sizeof(h_flag_t);
#if defined(BOARD_USE_EXTERNAL_FLASH)
int rv = up_progmem_ext_write((size_t) &pf->flag, &data, size);
#else
int rv = up_progmem_write((size_t) &pf->flag, &data, size);
#endif
return rv;
}
@ -881,7 +894,11 @@ parameter_flashfs_write(flash_file_token_t token, uint8_t *buffer, size_t buf_si
}
pn->crc = crc32(entry_crc_start(pn), entry_crc_length(pn));
#if defined(BOARD_USE_EXTERNAL_FLASH)
rv = up_progmem_ext_write((size_t) pf, pn, pn->size);
#else
rv = up_progmem_write((size_t) pf, pn, pn->size);
#endif
int system_bytes = (sizeof(flash_entry_header_t) + size_adjust);
if (rv >= system_bytes) {

View File

@ -98,7 +98,7 @@ __EXPORT extern const flash_file_token_t parameters_token;
*
*/
typedef struct sector_descriptor_t {
uint8_t page;
uint16_t page;
uint32_t size;
uint32_t address;
} sector_descriptor_t;