Viktor Vladic
3 years ago
committed by
GitHub
26 changed files with 2685 additions and 0 deletions
@ -0,0 +1,3 @@
@@ -0,0 +1,3 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" |
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7" |
||||
CONFIG_BOARD_ROMFSROOT="" |
@ -0,0 +1,82 @@
@@ -0,0 +1,82 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" |
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7" |
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1" |
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2" |
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" |
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" |
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" |
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y |
||||
CONFIG_COMMON_BAROMETERS=y |
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y |
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y |
||||
CONFIG_COMMON_DISTANCE_SENSOR=y |
||||
CONFIG_DRIVERS_DSHOT=y |
||||
CONFIG_DRIVERS_GPS=y |
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y |
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y |
||||
CONFIG_COMMON_LIGHT=y |
||||
CONFIG_COMMON_MAGNETOMETER=y |
||||
CONFIG_COMMON_OPTICAL_FLOW=y |
||||
CONFIG_DRIVERS_OSD=y |
||||
CONFIG_DRIVERS_PWM_OUT=y |
||||
CONFIG_DRIVERS_PWM_OUT_SIM=y |
||||
CONFIG_DRIVERS_RC_INPUT=y |
||||
CONFIG_DRIVERS_RPM=y |
||||
CONFIG_COMMON_TELEMETRY=y |
||||
CONFIG_DRIVERS_TONE_ALARM=y |
||||
CONFIG_DRIVERS_UAVCAN=y |
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y |
||||
CONFIG_MODULES_BATTERY_STATUS=y |
||||
CONFIG_MODULES_COMMANDER=y |
||||
CONFIG_MODULES_DATAMAN=y |
||||
CONFIG_MODULES_EKF2=y |
||||
CONFIG_MODULES_EVENTS=y |
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y |
||||
CONFIG_MODULES_GYRO_CALIBRATION=y |
||||
CONFIG_MODULES_GYRO_FFT=y |
||||
CONFIG_MODULES_LAND_DETECTOR=y |
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y |
||||
CONFIG_MODULES_LOAD_MON=y |
||||
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y |
||||
CONFIG_MODULES_LOGGER=y |
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y |
||||
CONFIG_MODULES_MAVLINK=y |
||||
CONFIG_MODULES_MC_ATT_CONTROL=y |
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y |
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y |
||||
CONFIG_MODULES_MC_POS_CONTROL=y |
||||
CONFIG_MODULES_MC_RATE_CONTROL=y |
||||
CONFIG_MODULES_NAVIGATOR=y |
||||
CONFIG_MODULES_RC_UPDATE=y |
||||
CONFIG_MODULES_SENSORS=y |
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y |
||||
CONFIG_MODULES_VMOUNT=y |
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y |
||||
CONFIG_SYSTEMCMDS_DMESG=y |
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y |
||||
CONFIG_SYSTEMCMDS_ESC_CALIB=y |
||||
CONFIG_SYSTEMCMDS_GPIO=y |
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y |
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y |
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y |
||||
CONFIG_SYSTEMCMDS_MFT=y |
||||
CONFIG_SYSTEMCMDS_MIXER=y |
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y |
||||
CONFIG_SYSTEMCMDS_MTD=y |
||||
CONFIG_SYSTEMCMDS_NSHTERM=y |
||||
CONFIG_SYSTEMCMDS_PARAM=y |
||||
CONFIG_SYSTEMCMDS_PERF=y |
||||
CONFIG_SYSTEMCMDS_PWM=y |
||||
CONFIG_SYSTEMCMDS_REBOOT=y |
||||
CONFIG_SYSTEMCMDS_SD_BENCH=y |
||||
CONFIG_SYSTEMCMDS_SD_STRESS=y |
||||
CONFIG_SYSTEMCMDS_SERIAL_TEST=y |
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y |
||||
CONFIG_SYSTEMCMDS_TOP=y |
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y |
||||
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y |
||||
CONFIG_SYSTEMCMDS_UORB=y |
||||
CONFIG_SYSTEMCMDS_USB_CONNECTED=y |
||||
CONFIG_SYSTEMCMDS_VER=y |
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y |
||||
CONFIG_EXAMPLES_FAKE_GPS=y |
@ -0,0 +1,13 @@
@@ -0,0 +1,13 @@
|
||||
{ |
||||
"board_id": 139, |
||||
"magic": "PX4FWv1", |
||||
"description": "Firmware for the MatekH743-slim board", |
||||
"image": "", |
||||
"build_time": 0, |
||||
"summary": "MatekH743-slim", |
||||
"version": "0.1", |
||||
"image_size": 0, |
||||
"image_maxsize": 1966080, |
||||
"git_identity": "", |
||||
"board_revision": 0 |
||||
} |
@ -0,0 +1,16 @@
@@ -0,0 +1,16 @@
|
||||
#!/bin/sh |
||||
# |
||||
# board specific extras init |
||||
#------------------------------------------------------------------------------ |
||||
|
||||
# if ! param compare OSD_ATXXXX_CFG 0 |
||||
# then |
||||
# atxxxx start -s |
||||
# fi |
||||
|
||||
atxxxx start -s |
||||
|
||||
|
||||
# DShot telemetry is always on UART7 |
||||
# dshot telemetry /dev/ttyS5 |
||||
|
@ -0,0 +1,18 @@
@@ -0,0 +1,18 @@
|
||||
#!/bin/sh |
||||
# |
||||
# board specific sensors init |
||||
#------------------------------------------------------------------------------ |
||||
|
||||
board_adc start |
||||
|
||||
# Internal SPI bus ICM-20602 |
||||
icm20602 -R 12 -s start |
||||
|
||||
# Internal SPI bus MPU-6000 |
||||
mpu6000 -R 12 -s start |
||||
|
||||
# Internal baro |
||||
dps310 -I start -a 118 |
||||
|
||||
# External mag |
||||
qmc5883l -X start -a 13 |
@ -0,0 +1,17 @@
@@ -0,0 +1,17 @@
|
||||
# |
||||
# 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. |
@ -0,0 +1,93 @@
@@ -0,0 +1,93 @@
|
||||
# |
||||
# 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_DEV_CONSOLE is not set |
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set |
||||
# CONFIG_SPI_EXCHANGE is not set |
||||
# CONFIG_STM32H7_SYSCFG 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_STM32H743VI=y |
||||
CONFIG_ARCH_CHIP_STM32H7=y |
||||
CONFIG_ARCH_INTERRUPTSTACK=512 |
||||
CONFIG_ARMV7M_BASEPRI_WAR=y |
||||
CONFIG_ARMV7M_ICACHE=y |
||||
CONFIG_ARMV7M_MEMCPY=y |
||||
CONFIG_ARMV7M_USEBASEPRI=y |
||||
CONFIG_BOARDCTL_RESET=y |
||||
CONFIG_BOARD_INITTHREAD_PRIORITY=254 |
||||
CONFIG_BOARD_LATE_INITIALIZE=y |
||||
CONFIG_BOARD_LOOPSPERMSEC=22114 |
||||
CONFIG_BOARD_RESET_ON_ASSERT=2 |
||||
CONFIG_C99_BOOL8=y |
||||
CONFIG_CDCACM=y |
||||
CONFIG_CDCACM_PRODUCTID=0x004b |
||||
CONFIG_CDCACM_PRODUCTSTR="Matek H743-slim" |
||||
CONFIG_CDCACM_RXBUFSIZE=600 |
||||
CONFIG_CDCACM_TXBUFSIZE=12000 |
||||
CONFIG_CDCACM_VENDORID=0x3162 |
||||
CONFIG_CDCACM_VENDORSTR="Matek" |
||||
CONFIG_CLOCK_MONOTONIC=y |
||||
CONFIG_DEBUG_FULLOPT=y |
||||
CONFIG_DEBUG_SYMBOLS=y |
||||
CONFIG_DEFAULT_SMALL=y |
||||
CONFIG_DISABLE_MQUEUE=y |
||||
CONFIG_DISABLE_PTHREAD=y |
||||
CONFIG_EXPERIMENTAL=y |
||||
CONFIG_FDCLONE_DISABLE=y |
||||
CONFIG_FDCLONE_STDIO=y |
||||
CONFIG_HAVE_CXX=y |
||||
CONFIG_HAVE_CXXINITIALIZE=y |
||||
CONFIG_IDLETHREAD_STACKSIZE=750 |
||||
CONFIG_LIBC_FLOATINGPOINT=y |
||||
CONFIG_LIBC_LONG_LONG=y |
||||
CONFIG_LIBC_STRERROR=y |
||||
CONFIG_LIB_BOARDCTL=y |
||||
CONFIG_FS_PROCFS_MAX_TASKS=8 |
||||
CONFIG_MEMSET_64BIT=y |
||||
CONFIG_MEMSET_OPTSPEED=y |
||||
CONFIG_PREALLOC_TIMERS=50 |
||||
CONFIG_PTHREAD_STACK_MIN=512 |
||||
CONFIG_RAM_SIZE=245760 |
||||
CONFIG_RAM_START=0x20010000 |
||||
CONFIG_RAW_BINARY=y |
||||
CONFIG_SDCLONE_DISABLE=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_SPI=y |
||||
CONFIG_STACK_COLORATION=y |
||||
CONFIG_START_DAY=30 |
||||
CONFIG_START_MONTH=11 |
||||
CONFIG_STDIO_BUFFER_SIZE=32 |
||||
CONFIG_STM32H7_BKPSRAM=y |
||||
CONFIG_STM32H7_DMA1=y |
||||
CONFIG_STM32H7_OTGFS=y |
||||
CONFIG_STM32H7_PROGMEM=y |
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y |
||||
CONFIG_STM32H7_TIM1=y |
||||
CONFIG_STM32H7_USART1=y |
||||
CONFIG_SYSTEMTICK_HOOK=y |
||||
CONFIG_SYSTEM_CDCACM=y |
||||
CONFIG_TASK_NAME_SIZE=24 |
||||
CONFIG_TTY_SIGINT=y |
||||
CONFIG_TTY_SIGINT_CHAR=0x03 |
||||
CONFIG_TTY_SIGTSTP=y |
||||
CONFIG_USART1_RXBUFSIZE=600 |
||||
CONFIG_USART1_TXBUFSIZE=300 |
||||
CONFIG_USBDEV=y |
||||
CONFIG_USBDEV_BUSPOWERED=y |
||||
CONFIG_USBDEV_MAXPOWER=500 |
||||
CONFIG_USEC_PER_TICK=1000 |
||||
CONFIG_USERMAIN_STACKSIZE=2944 |
||||
CONFIG_USER_ENTRYPOINT="bootloader_main" |
@ -0,0 +1,493 @@
@@ -0,0 +1,493 @@
|
||||
/************************************************************************************
|
||||
* nuttx-configs/px4_fmu-v6u/include/board.h |
||||
* |
||||
* Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. |
||||
* Authors: David Sidrane <david.sidrane@nscdg.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_MATEKH743SLIM_INCLUDE_BOARD_H |
||||
#define __NUTTX_CONFIG_MATEKH743SLIM_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 MatekH743-Slim board provides the following clock sources:
|
||||
* |
||||
* X1: 8 MHz crystal for HSE |
||||
* |
||||
* So we have these clock source available within the STM32 |
||||
* |
||||
* HSI: 64 MHz RC factory-trimmed |
||||
* HSE: 8 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 = (8,000,000 / 1) * 120 = 960 MHz |
||||
* |
||||
* PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz |
||||
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz |
||||
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 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(1) |
||||
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(120) |
||||
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) |
||||
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) |
||||
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) |
||||
|
||||
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 120) |
||||
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) |
||||
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) |
||||
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) |
||||
|
||||
/* 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(2) |
||||
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) |
||||
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) |
||||
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) |
||||
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) |
||||
|
||||
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48) |
||||
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) |
||||
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) |
||||
#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_DIVQ3EN) |
||||
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(2) |
||||
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) |
||||
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) |
||||
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) |
||||
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) |
||||
|
||||
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48) |
||||
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) |
||||
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) |
||||
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) |
||||
|
||||
/* SYSCLK = PLL1P = 480MHz
|
||||
* CPUCLK = SYSCLK / 1 = 480 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 (240 MHz max)
|
||||
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 |
||||
*/ |
||||
|
||||
#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 (120 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 (120 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 (120 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 (120 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 |
||||
|
||||
/* I2C4 clock source */ |
||||
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI |
||||
|
||||
/* SPI123 clock source */ |
||||
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 |
||||
|
||||
/* SPI45 clock source */ |
||||
|
||||
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 |
||||
|
||||
/* SPI6 clock source */ |
||||
|
||||
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 |
||||
|
||||
/* USB 1 and 2 clock source */ |
||||
|
||||
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 |
||||
|
||||
/* ADC 1 2 3 clock source */ |
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 |
||||
|
||||
/* FDCAN 1 clock source */ |
||||
|
||||
#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ |
||||
|
||||
#define STM32_FDCANCLK STM32_HSE_FREQUENCY |
||||
|
||||
/* 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 480kHz, 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 board has two, LED_GREEN a Green LED and LED_BLUE a Blue LED,
|
||||
* that 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_LED2 1 |
||||
#define BOARD_NLEDS 2 |
||||
|
||||
#define BOARD_LED_BLUE BOARD_LED1 |
||||
#define BOARD_LED_GREEN BOARD_LED2 |
||||
|
||||
/* LED bits for use with board_userled_all() */ |
||||
|
||||
#define BOARD_LED1_BIT (1 << BOARD_LED1) |
||||
#define BOARD_LED2_BIT (1 << BOARD_LED2) |
||||
|
||||
/* 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 is sleep mode ON OFF OFF */ |
||||
|
||||
/* Thus if the Green LED is statically on, NuttX has successfully booted and
|
||||
* is, apparently, running normally. If the Red LED is flashing at |
||||
* approximately 2Hz, then a fatal error has been detected and the system |
||||
* has halted. |
||||
*/ |
||||
|
||||
/* Alternate function pin selections ************************************************/ |
||||
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PA10 */ |
||||
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */ |
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ |
||||
#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_3 /* PB8 */ |
||||
#define GPIO_UART4_TX GPIO_UART4_TX_3 /* PB9 */ |
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ |
||||
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ |
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ |
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ |
||||
#define GPIO_UART7_RTS GPIO_UART7_RTS_1 /* PE9 */ |
||||
#define GPIO_UART7_CTS GPIO_UART7_CTS_1 /* PE10 */ |
||||
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ |
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ |
||||
|
||||
|
||||
/* CAN
|
||||
* |
||||
* CAN1 is routed to transceiver. |
||||
*/ |
||||
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ |
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ |
||||
|
||||
/* SPI
|
||||
* |
||||
* SPI1 is MPU6000 |
||||
* SPI2 is MAX7456 |
||||
* SPI3 is extern with PD4 and PE2 as CS |
||||
* SPI4 is ICM20602 |
||||
*/ |
||||
|
||||
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) |
||||
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ |
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */ |
||||
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ |
||||
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */ |
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */ |
||||
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_4) /* PB13 */ |
||||
|
||||
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */ |
||||
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_4 /* PB5 */ |
||||
#define GPIO_SPI3_SCK ADJ_SLEW_RATE(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 ADJ_SLEW_RATE(GPIO_SPI4_SCK_1) /* PE12 */ |
||||
|
||||
/* I2C
|
||||
* |
||||
* 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_1 /* PB6 */ |
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */ |
||||
|
||||
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6) |
||||
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7) |
||||
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */ |
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */ |
||||
|
||||
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10) |
||||
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11) |
||||
|
||||
/* SDMMC1
|
||||
* |
||||
* SDMMC1_D0 PC8 |
||||
* SDMMC1_D1 PC9 |
||||
* SDMMC1_D2 PC10 |
||||
* SDMMC1_D3 PC11 |
||||
* SDMMC1_CK PC12 |
||||
* SDMMC1_CMD PD2 |
||||
*/ |
||||
|
||||
// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0 /* PC8 */
|
||||
// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1 /* PC9 */
|
||||
// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2 /* PC10 */
|
||||
// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 /* PC11 */
|
||||
// #define GPIO_SDMMC1_CK GPIO_SDMMC1_CK /* PC12 */
|
||||
// #define GPIO_SDMMC1_CMD GPIO_SDMMC1_CMD /* PD2 */
|
||||
|
||||
|
||||
/* 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_PORTI|GPIO_PIN0) /* PI0 AUX1 */ |
||||
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ |
||||
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ |
||||
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 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 AUX6 */ |
||||
# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ |
||||
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ |
||||
# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 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); } \
|
||||
} 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 |
||||
|
||||
#endif /*__NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H */ |
@ -0,0 +1,43 @@
@@ -0,0 +1,43 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2021 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 |
||||
|
||||
// DMAMUX1
|
||||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */ |
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */ |
||||
|
||||
|
||||
// DMAMUX2
|
||||
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* DMA2:83 */ |
||||
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* DMA2:84 */ |
@ -0,0 +1,226 @@
@@ -0,0 +1,226 @@
|
||||
# |
||||
# 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_ENVIRON 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_STM32H743VI=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_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=0x0036 |
||||
CONFIG_CDCACM_PRODUCTSTR="MatekH743-slim" |
||||
CONFIG_CDCACM_RXBUFSIZE=600 |
||||
CONFIG_CDCACM_TXBUFSIZE=12000 |
||||
CONFIG_CDCACM_VENDORID=0x1B8C |
||||
CONFIG_CDCACM_VENDORSTR="PX4" |
||||
CONFIG_CLOCK_MONOTONIC=y |
||||
CONFIG_DEBUG_FULLOPT=y |
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y |
||||
CONFIG_DEBUG_MEMFAULT=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_MAX_TASKS=64 |
||||
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_MEMSET_64BIT=y |
||||
CONFIG_MEMSET_OPTSPEED=y |
||||
CONFIG_MMCSD=y |
||||
CONFIG_MMCSD_SDIO=y |
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y |
||||
CONFIG_MM_REGIONS=4 |
||||
CONFIG_NAME_MAX=40 |
||||
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_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_OTG_ID_GPIO_DISABLE=y |
||||
CONFIG_PIPES=y |
||||
CONFIG_PREALLOC_TIMERS=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_INSTRUMENTATION_EXTERNAL=y |
||||
CONFIG_SCHED_LPWORK=y |
||||
CONFIG_SCHED_LPWORKPRIORITY=50 |
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632 |
||||
CONFIG_SCHED_WAITPID=y |
||||
CONFIG_SDCLONE_DISABLE=y |
||||
CONFIG_SDMMC1_SDIO_PULLUP=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=256 |
||||
CONFIG_STM32H7_ADC1=y |
||||
CONFIG_STM32H7_ADC3=y |
||||
CONFIG_STM32H7_BBSRAM=y |
||||
CONFIG_STM32H7_BBSRAM_FILES=5 |
||||
CONFIG_STM32H7_BDMA=y |
||||
CONFIG_STM32H7_BKPSRAM=y |
||||
CONFIG_STM32H7_DMA1=y |
||||
CONFIG_STM32H7_DMA2=y |
||||
CONFIG_STM32H7_DMACAPABLE=y |
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y |
||||
CONFIG_STM32H7_I2C1=y |
||||
CONFIG_STM32H7_I2C2=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_SPI1=y |
||||
CONFIG_STM32H7_SPI1_DMA=y |
||||
CONFIG_STM32H7_SPI1_DMA_BUFFER=2048 |
||||
CONFIG_STM32H7_SPI2=y |
||||
CONFIG_STM32H7_SPI3=y |
||||
CONFIG_STM32H7_SPI4=y |
||||
CONFIG_STM32H7_SPI4_DMA=y |
||||
CONFIG_STM32H7_SPI4_DMA_BUFFER=2048 |
||||
CONFIG_STM32H7_SPI_DMA=y |
||||
CONFIG_STM32H7_SPI_DMATHRESHOLD=8 |
||||
CONFIG_STM32H7_TIM15=y |
||||
CONFIG_STM32H7_TIM1=y |
||||
CONFIG_STM32H7_TIM2=y |
||||
CONFIG_STM32H7_TIM4=y |
||||
CONFIG_STM32H7_TIM5=y |
||||
CONFIG_STM32H7_TIM8=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_UART4_BAUD=57600 |
||||
CONFIG_UART4_RXBUFSIZE=600 |
||||
CONFIG_UART4_TXBUFSIZE=1500 |
||||
CONFIG_UART7_BAUD=57600 |
||||
CONFIG_UART7_IFLOWCONTROL=y |
||||
CONFIG_UART7_OFLOWCONTROL=y |
||||
CONFIG_UART7_RXBUFSIZE=600 |
||||
CONFIG_UART7_TXBUFSIZE=1500 |
||||
CONFIG_UART8_BAUD=57600 |
||||
CONFIG_UART8_RXBUFSIZE=600 |
||||
CONFIG_UART8_TXBUFSIZE=1500 |
||||
CONFIG_USART1_BAUD=57600 |
||||
CONFIG_USART1_RXBUFSIZE=600 |
||||
CONFIG_USART1_SERIAL_CONSOLE=y |
||||
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=1500 |
||||
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=2944 |
||||
CONFIG_USER_ENTRYPOINT="nsh_main" |
||||
CONFIG_WATCHDOG=y |
@ -0,0 +1,213 @@
@@ -0,0 +1,213 @@
|
||||
/**************************************************************************** |
||||
* scripts/script.ld |
||||
* |
||||
* Copyright (C) 2016, 2019 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/* The Durandal-v1 uses an STM32H743II has 2048Kb of main 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 Durandal 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 SRAM1 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 |
||||
* |
||||
* SRAM1 - 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 |
||||
{ |
||||
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K |
||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K |
||||
dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K |
||||
dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K |
||||
sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K |
||||
sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K |
||||
sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K |
||||
sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K |
||||
sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K |
||||
bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K |
||||
} |
||||
|
||||
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 |
||||
{ |
||||
.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.*) |
||||
*(.fixup) |
||||
*(.gnu.warning) |
||||
*(.rodata .rodata.*) |
||||
*(.gnu.linkonce.t.*) |
||||
*(.glue_7) |
||||
*(.glue_7t) |
||||
*(.got) |
||||
*(.gcc_except_table) |
||||
*(.gnu.linkonce.r.*) |
||||
_etext = ABSOLUTE(.); |
||||
|
||||
} > flash |
||||
|
||||
/* |
||||
* Init functions (static constructors and the like) |
||||
*/ |
||||
.init_section : { |
||||
_sinit = ABSOLUTE(.); |
||||
KEEP(*(.init_array .init_array.*)) |
||||
_einit = ABSOLUTE(.); |
||||
} > flash |
||||
|
||||
|
||||
.ARM.extab : { |
||||
*(.ARM.extab*) |
||||
} > flash |
||||
|
||||
__exidx_start = ABSOLUTE(.); |
||||
.ARM.exidx : { |
||||
*(.ARM.exidx*) |
||||
} > flash |
||||
__exidx_end = ABSOLUTE(.); |
||||
|
||||
_eronly = ABSOLUTE(.); |
||||
|
||||
.data : { |
||||
_sdata = ABSOLUTE(.); |
||||
*(.data .data.*) |
||||
*(.gnu.linkonce.d.*) |
||||
CONSTRUCTORS |
||||
_edata = ABSOLUTE(.); |
||||
} > sram AT > flash |
||||
|
||||
.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) } |
||||
} |
@ -0,0 +1,222 @@
@@ -0,0 +1,222 @@
|
||||
/**************************************************************************** |
||||
* scripts/script.ld |
||||
* |
||||
* Copyright (C) 2016, 2019 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/* The Durandal-v1 uses an STM32H743II has 2048Kb of main 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 Durandal 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 SRAM1 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 |
||||
* |
||||
* SRAM1 - 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 |
||||
{ |
||||
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K |
||||
flash (rx) : ORIGIN = 0x08020000, LENGTH = 1920K |
||||
dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K |
||||
dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K |
||||
sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K |
||||
sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K |
||||
sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K |
||||
sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K |
||||
sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K |
||||
bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K |
||||
} |
||||
|
||||
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 |
||||
{ |
||||
.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.*) |
||||
*(.fixup) |
||||
*(.gnu.warning) |
||||
*(.rodata .rodata.*) |
||||
*(.gnu.linkonce.t.*) |
||||
*(.glue_7) |
||||
*(.glue_7t) |
||||
*(.got) |
||||
*(.gcc_except_table) |
||||
*(.gnu.linkonce.r.*) |
||||
_etext = ABSOLUTE(.); |
||||
|
||||
} > flash |
||||
|
||||
/* |
||||
* Init functions (static constructors and the like) |
||||
*/ |
||||
.init_section : { |
||||
_sinit = ABSOLUTE(.); |
||||
KEEP(*(.init_array .init_array.*)) |
||||
_einit = ABSOLUTE(.); |
||||
} > flash |
||||
|
||||
|
||||
.ARM.extab : { |
||||
*(.ARM.extab*) |
||||
} > flash |
||||
|
||||
__exidx_start = ABSOLUTE(.); |
||||
.ARM.exidx : { |
||||
*(.ARM.exidx*) |
||||
} > flash |
||||
__exidx_end = ABSOLUTE(.); |
||||
|
||||
_eronly = ABSOLUTE(.); |
||||
|
||||
.data : { |
||||
_sdata = ABSOLUTE(.); |
||||
*(.data .data.*) |
||||
*(.gnu.linkonce.d.*) |
||||
CONSTRUCTORS |
||||
_edata = ABSOLUTE(.); |
||||
} > sram AT > flash |
||||
|
||||
.bss : { |
||||
_sbss = ABSOLUTE(.); |
||||
*(.bss .bss.*) |
||||
*(.gnu.linkonce.b.*) |
||||
*(COMMON) |
||||
. = ALIGN(4); |
||||
_ebss = ABSOLUTE(.); |
||||
} > sram |
||||
|
||||
/* Emit the the D3 power domain section for locating BDMA data */ |
||||
|
||||
.sram4_reserve (NOLOAD) : |
||||
{ |
||||
*(.sram4) |
||||
. = ALIGN(4); |
||||
_sram4_heap_start = ABSOLUTE(.); |
||||
} > sram4 |
||||
|
||||
/* 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) } |
||||
} |
@ -0,0 +1,67 @@
@@ -0,0 +1,67 @@
|
||||
############################################################################ |
||||
# |
||||
# Copyright (c) 2021 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. |
||||
# |
||||
############################################################################ |
||||
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") |
||||
add_library(drivers_board |
||||
bootloader_main.c |
||||
usb.c |
||||
) |
||||
target_link_libraries(drivers_board |
||||
PRIVATE |
||||
nuttx_arch |
||||
nuttx_drivers |
||||
bootloader |
||||
) |
||||
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) |
||||
|
||||
else() |
||||
add_library(drivers_board |
||||
i2c.cpp |
||||
init.c |
||||
led.c |
||||
sdio.c |
||||
spi.cpp |
||||
timer_config.cpp |
||||
usb.c |
||||
) |
||||
add_dependencies(drivers_board arch_board_hw_info) |
||||
|
||||
target_link_libraries(drivers_board |
||||
PRIVATE |
||||
arch_spi |
||||
arch_board_hw_info |
||||
drivers__led |
||||
nuttx_arch |
||||
nuttx_drivers |
||||
px4_layer |
||||
) |
||||
endif() |
@ -0,0 +1,237 @@
@@ -0,0 +1,237 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2021 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 board_config.h |
||||
* |
||||
* Board 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
|
||||
|
||||
|
||||
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ |
||||
|
||||
#define GPIO_nLED_BLUE /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) |
||||
#define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) |
||||
|
||||
#define BOARD_HAS_CONTROL_STATUS_LEDS 1 |
||||
#define BOARD_ARMED_STATE_LED 1 // Green LED
|
||||
#define BOARD_OVERLOAD_LED 0 // Blue LED
|
||||
|
||||
|
||||
/*
|
||||
* 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 |
||||
*/ |
||||
|
||||
/* ADC defines to be used in sensors.cpp to read from a particular channel */ |
||||
#define ADC1_CH(n) (n) |
||||
|
||||
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ |
||||
#define PX4_ADC_GPIO \ |
||||
/* PC0 */ GPIO_ADC123_INP10, \
|
||||
/* PC1 */ GPIO_ADC123_INP11, \
|
||||
/* PA4 */ GPIO_ADC12_INP18, \
|
||||
/* PA7 */ GPIO_ADC12_INP7, \
|
||||
/* PC4 */ GPIO_ADC12_INP4, \
|
||||
/* PC5 */ GPIO_ADC12_INP8 |
||||
|
||||
/* Define Channel numbers must match above GPIO pin IN(n)*/ |
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC0 */ ADC1_CH(10) |
||||
#define ADC_BATTERY_CURRENT_CHANNEL /* PC1 */ ADC1_CH(11) |
||||
#define ADC_BATTERY2_VOLTAGE_CHANNEL /* PA4 */ ADC1_CH(18) |
||||
#define ADC_BATTERY2_CURRENT_CHANNEL /* PA7 */ ADC1_CH(7) |
||||
#define ADC_AIRSPEED_IN_CHANNEL /* PC4 */ ADC1_CH(4) |
||||
#define ADC_RSSI_IN_CHANNEL /* PC5 */ ADC1_CH(8) |
||||
|
||||
#define ADC_CHANNELS \ |
||||
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_AIRSPEED_IN_CHANNEL) | \
|
||||
(1 << ADC_RSSI_IN_CHANNEL)) |
||||
|
||||
|
||||
/* Define Battery 1 Voltage Divider and A per V
|
||||
*/ |
||||
|
||||
#define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ |
||||
#define BOARD_BATTERY1_A_PER_V (40.0f) |
||||
#define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ |
||||
|
||||
|
||||
/* CAN Silence
|
||||
* |
||||
* Silent mode control \ ESC Mux select |
||||
*/ |
||||
|
||||
#define GPIO_CAN1_SILENT_S0 /* PD3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN3) |
||||
|
||||
|
||||
/* PWM
|
||||
*/ |
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8 |
||||
#define DIRECT_INPUT_TIMER_CHANNELS 8 |
||||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS |
||||
|
||||
|
||||
/* Spare GPIO */ |
||||
|
||||
// #define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6)
|
||||
// #define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15)
|
||||
// #define GPIO_PG15 /* PG15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN15)
|
||||
|
||||
|
||||
/* Tone alarm output */ |
||||
|
||||
#define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) |
||||
#define GPIO_TONE_ALARM_GPIO /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) |
||||
|
||||
// #define TONE_ALARM_TIMER 2 /* Timer 2 */
|
||||
// #define TONE_ALARM_CHANNEL 1 /* PA15 GPIO_TIM2_CH1OUT_2 */
|
||||
// #define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
|
||||
// #define GPIO_TONE_ALARM GPIO_TIM2_CH1OUT_2
|
||||
|
||||
|
||||
/* USB OTG FS
|
||||
* |
||||
* PE2 OTG_FS_VBUS VBUS sensing |
||||
*/ |
||||
|
||||
#define GPIO_OTGFS_VBUS /* PE2 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN2) |
||||
|
||||
|
||||
/* High-resolution timer */ |
||||
#define HRT_TIMER 2 /* use timer8 for the HRT */ |
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 3 */ |
||||
|
||||
|
||||
/* RC Serial port */ |
||||
#define RC_SERIAL_PORT "/dev/ttyS4" |
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT |
||||
|
||||
// #define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
|
||||
|
||||
|
||||
/* SD Card */ |
||||
#define SDIO_SLOTNO 0 /* Only one slot */ |
||||
#define SDIO_MINOR 0 |
||||
|
||||
/* 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_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN1_SILENT_S0, \
|
||||
GPIO_nLED_BLUE, \
|
||||
GPIO_nLED_GREEN, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
} |
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER |
||||
|
||||
#define BOARD_NUM_IO_TIMERS 4 |
||||
|
||||
|
||||
__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> |
||||
|
||||
#endif /* __ASSEMBLY__ */ |
||||
|
||||
__END_DECLS |
@ -0,0 +1,75 @@
@@ -0,0 +1,75 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2021 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 bootloader_main.c |
||||
* |
||||
* FMU-specific early startup code for bootloader |
||||
*/ |
||||
|
||||
#include "board_config.h" |
||||
#include "bl.h" |
||||
|
||||
#include <nuttx/config.h> |
||||
#include <nuttx/board.h> |
||||
#include <chip.h> |
||||
#include <stm32_uart.h> |
||||
#include <arch/board/board.h> |
||||
#include "arm_internal.h" |
||||
#include <px4_platform_common/init.h> |
||||
|
||||
extern int sercon_main(int c, char **argv); |
||||
|
||||
__EXPORT void board_on_reset(int status) {} |
||||
|
||||
__EXPORT void stm32_boardinitialize(void) |
||||
{ |
||||
/* configure USB interfaces */ |
||||
stm32_usbinitialize(); |
||||
} |
||||
|
||||
__EXPORT int board_app_initialize(uintptr_t arg) |
||||
{ |
||||
return 0; |
||||
} |
||||
|
||||
void board_late_initialize(void) |
||||
{ |
||||
sercon_main(0, NULL); |
||||
} |
||||
|
||||
extern void sys_tick_handler(void); |
||||
void board_timerhook(void) |
||||
{ |
||||
sys_tick_handler(); |
||||
} |
@ -0,0 +1,135 @@
@@ -0,0 +1,135 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2021 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 |
||||
|
||||
/****************************************************************************
|
||||
* 10-8--2016: |
||||
* To simplify the ripple effect on the tools, we will be using |
||||
* /dev/serial/by-id/<asterisk>PX4<asterisk> to locate PX4 devices. Therefore |
||||
* moving forward all Bootloaders must contain the prefix "PX4 BL " |
||||
* in the USBDEVICESTRING |
||||
* This Change will be made in an upcoming BL release |
||||
****************************************************************************/ |
||||
/*
|
||||
* Define usage to configure a bootloader |
||||
* |
||||
* |
||||
* Constant example Usage |
||||
* APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed |
||||
* BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request |
||||
* BOARD_FMUV2 |
||||
* INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading |
||||
* INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading |
||||
* USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string |
||||
* USBPRODUCTID 0x0011 - PID Should match defconfig |
||||
* BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom |
||||
* delay provided by an APP FW |
||||
* BOARD_TYPE 9 - Must match .prototype boad_id |
||||
* _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection |
||||
* BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector |
||||
* BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector |
||||
* BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. |
||||
* (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted |
||||
* programmatically |
||||
* |
||||
* BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. |
||||
* This is to allow sectors to be reserved for app fw usage. That will NOT be erased |
||||
* during a FW upgrade. |
||||
* The default is 0, and selects the first sector to be erased, as the 0th entry in the |
||||
* flash_sectors table. Which is the second physical sector of FLASH in the device. |
||||
* The first physical sector of FLASH is used by the bootloader, and is not defined |
||||
* in the table. |
||||
* |
||||
* APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus |
||||
* BOOTLOADER_RESERVATION_SIZE will be deducted from |
||||
* BOARD_FLASH_SIZE to determine the size of the App FW |
||||
* and hence the address space of FLASH to erase and program. |
||||
* USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) |
||||
* SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL |
||||
* |
||||
* * Other defines are somewhat self explanatory. |
||||
*/ |
||||
|
||||
/* Boot device selection list*/ |
||||
#define USB0_DEV 0x01 |
||||
#define SERIAL0_DEV 0x02 |
||||
#define SERIAL1_DEV 0x04 |
||||
|
||||
#define APP_LOAD_ADDRESS 0x08020000 |
||||
#define BOOTLOADER_DELAY 5000 |
||||
#define INTERFACE_USB 1 |
||||
#define INTERFACE_USB_CONFIG "/dev/ttyACM0" |
||||
#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) |
||||
|
||||
//#define USE_VBUS_PULL_DOWN
|
||||
#define INTERFACE_USART 1 |
||||
#define INTERFACE_USART_CONFIG "/dev/ttyS0,57600" |
||||
#define BOOT_DELAY_ADDRESS 0x000001a0 |
||||
#define BOARD_TYPE 139 |
||||
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) |
||||
#define BOARD_FLASH_SECTORS (15) |
||||
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) |
||||
|
||||
#define OSC_FREQ 8 |
||||
|
||||
#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE
|
||||
#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN
|
||||
#define BOARD_LED_ON 0 |
||||
#define BOARD_LED_OFF 1 |
||||
|
||||
#define SERIAL_BREAK_DETECT_DISABLED 1 |
||||
|
||||
#if !defined(ARCH_SN_MAX_LENGTH) |
||||
# define ARCH_SN_MAX_LENGTH 12 |
||||
#endif |
||||
|
||||
#if !defined(APP_RESERVATION_SIZE) |
||||
# define APP_RESERVATION_SIZE 0 |
||||
#endif |
||||
|
||||
#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) |
||||
# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 |
||||
#endif |
||||
|
||||
#if !defined(USB_DATA_ALIGN) |
||||
# define USB_DATA_ALIGN |
||||
#endif |
||||
|
||||
#ifndef BOOT_DEVICES_SELECTION |
||||
# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV |
||||
#endif |
||||
|
||||
#ifndef BOOT_DEVICES_FILTER_ONUSB |
||||
# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV |
||||
#endif |
@ -0,0 +1,39 @@
@@ -0,0 +1,39 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2021 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] = { |
||||
initI2CBusExternal(1), |
||||
initI2CBusInternal(2), |
||||
}; |
@ -0,0 +1,182 @@
@@ -0,0 +1,182 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2021 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 |
||||
* |
||||
* FMU-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. |
||||
*/ |
||||
|
||||
#include "board_config.h" |
||||
|
||||
#include <syslog.h> |
||||
|
||||
#include <nuttx/config.h> |
||||
#include <nuttx/board.h> |
||||
#include <nuttx/sdio.h> |
||||
#include <nuttx/mmcsd.h> |
||||
#include <arch/board/board.h> |
||||
#include "arm_internal.h" |
||||
|
||||
#include <drivers/drv_hrt.h> |
||||
#include <drivers/drv_board_led.h> |
||||
#include <systemlib/px4_macros.h> |
||||
#include <px4_arch/io_timer.h> |
||||
#include <px4_platform_common/init.h> |
||||
#include <px4_platform/gpio.h> |
||||
#include <px4_platform/board_dma_alloc.h> |
||||
|
||||
__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) |
||||
{ |
||||
/* Reset PWM first thing */ |
||||
board_on_reset(-1); |
||||
|
||||
/* 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(); |
||||
|
||||
} |
||||
|
||||
/****************************************************************************
|
||||
* 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; |
||||
* |
||||
* 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"); |
||||
} |
||||
|
||||
/* initial LED state */ |
||||
drv_led_start(); |
||||
led_off(LED_RED); |
||||
led_off(LED_BLUE); |
||||
|
||||
if (board_hardfault_init(2, true) != 0) { |
||||
led_on(LED_BLUE); |
||||
} |
||||
|
||||
#ifdef CONFIG_MMCSD |
||||
int ret = stm32_sdio_initialize(); |
||||
|
||||
if (ret != OK) { |
||||
led_on(LED_BLUE); |
||||
return ret; |
||||
} |
||||
|
||||
#endif |
||||
|
||||
/* Configure the HW based on the manifest */ |
||||
px4_platform_configure(); |
||||
|
||||
return OK; |
||||
} |
@ -0,0 +1,112 @@
@@ -0,0 +1,112 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2021 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 led.c |
||||
* |
||||
* 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 arm_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 |
||||
|
||||
# define xlat(p) (p) |
||||
static uint32_t g_ledmap[] = { |
||||
GPIO_nLED_BLUE, // Indexed by LED_BLUE (defaulted to an output)
|
||||
GPIO_nLED_GREEN |
||||
}; |
||||
|
||||
__EXPORT void led_init(void) |
||||
{ |
||||
/* Configure LED GPIOs for output */ |
||||
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))); |
||||
} |
@ -0,0 +1,177 @@
@@ -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 */ |
@ -0,0 +1,55 @@
@@ -0,0 +1,55 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2021 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::SPI1, { |
||||
initSPIDevice(DRV_IMU_DEVTYPE_MPU6000, SPI::CS{GPIO::PortC, GPIO::Pin15}, SPI::DRDY{GPIO::PortB, GPIO::Pin1}), |
||||
}), |
||||
initSPIBus(SPI::Bus::SPI2, { |
||||
initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}), |
||||
}), |
||||
initSPIBusExternal(SPI::Bus::SPI3, { |
||||
initSPIConfigExternal(SPI::CS{GPIO::PortD, GPIO::Pin4}), |
||||
initSPIConfigExternal(SPI::CS{GPIO::PortE, GPIO::Pin2}), |
||||
}), |
||||
initSPIBus(SPI::Bus::SPI4, { |
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortE, GPIO::Pin11}), |
||||
}), |
||||
}; |
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses); |
@ -0,0 +1,82 @@
@@ -0,0 +1,82 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2021 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::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}), |
||||
initIOTimer(Timer::Timer5, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}), |
||||
initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}), |
||||
// initIOTimer(Timer::Timer15),
|
||||
}; |
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { |
||||
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}), |
||||
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}), |
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}), |
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}), |
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}), |
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}), |
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}), |
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), |
||||
// initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
|
||||
// initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}),
|
||||
// initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel1}, {GPIO::PortE, GPIO::Pin5}),
|
||||
// initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel2}, {GPIO::PortE, GPIO::Pin6}),
|
||||
}; |
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping = |
||||
initIOTimerChannelMapping(io_timers, timer_io_channels); |
||||
|
||||
|
||||
|
||||
constexpr io_timers_t led_pwm_timers[MAX_LED_TIMERS] = { |
||||
initIOTimer(Timer::Timer1), |
||||
}; |
||||
|
||||
// #define CCER_C1_NUM_BITS 4
|
||||
// #define POLARITY(c) (GTIM_CCER_CC1P << (((c)-1) * CCER_C1_NUM_BITS))
|
||||
// #define DRIVE_TYPE(p) ((p)|GPIO_OPENDRAIN|GPIO_PULLUP)
|
||||
|
||||
// static inline constexpr timer_io_channels_t initIOTimerChannelLED(const io_timers_t io_timers_conf[MAX_LED_TIMERS],
|
||||
// Timer::TimerChannel timer, GPIO::GPIOPin pin, int ui_polarity)
|
||||
// {
|
||||
// timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, timer, pin);
|
||||
// ret.gpio_out = DRIVE_TYPE(ret.gpio_out);
|
||||
// ret.masks = POLARITY(ui_polarity);
|
||||
// return ret;
|
||||
// }
|
||||
|
||||
// constexpr timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = {
|
||||
// initIOTimerChannelLED(led_pwm_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortA, GPIO::Pin8}, 1),
|
||||
// };
|
@ -0,0 +1,78 @@
@@ -0,0 +1,78 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2021 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 usb.c |
||||
* |
||||
* Board-specific USB functions. |
||||
*/ |
||||
|
||||
#include "board_config.h" |
||||
#include <nuttx/usb/usbdev.h> |
||||
#include <nuttx/usb/usbdev_trace.h> |
||||
#include <stm32_otg.h> |
||||
#include <debug.h> |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbinitialize |
||||
* |
||||
* Description: |
||||
* Called to setup USB-related GPIO pins for the 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_STM32F7_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); |
||||
} |
Loading…
Reference in new issue