forked from Archive/PX4-Autopilot
boards: add CUAV Nora support
This commit is contained in:
parent
942eb83184
commit
6937dbc5fd
|
@ -32,6 +32,7 @@ pipeline {
|
|||
"airmind_mindpx-v2_default",
|
||||
"av_x-v1_default",
|
||||
"bitcraze_crazyflie_default",
|
||||
"cuav_nora_default",
|
||||
"cuav_x7pro_default",
|
||||
"cubepilot_cubeorange_default",
|
||||
"cubepilot_cubeyellow_default",
|
||||
|
|
|
@ -18,6 +18,7 @@ jobs:
|
|||
airmind_mindpx-v2_default,
|
||||
av_x-v1_default,
|
||||
bitcraze_crazyflie_default,
|
||||
cuav_nora_default,
|
||||
cuav_x7pro_default,
|
||||
cubepilot_cubeorange_default,
|
||||
cubepilot_cubeyellow_default,
|
||||
|
|
|
@ -61,6 +61,11 @@ CONFIG:
|
|||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: av_x-v1_default
|
||||
cuav_nora_default:
|
||||
short: cuav_nora
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: cuav_nora_default
|
||||
cuav_x7pro_default:
|
||||
short: cuav_x7pro
|
||||
buildType: MinSizeRel
|
||||
|
|
|
@ -0,0 +1,9 @@
|
|||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR cuav
|
||||
MODEL nora
|
||||
LABEL bootloader
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
)
|
|
@ -0,0 +1,122 @@
|
|||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR cuav
|
||||
MODEL nora
|
||||
LABEL default
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
BUILD_BOOTLOADER
|
||||
TESTING
|
||||
# UAVCAN_INTERFACES 2 - No H7 or FD can support in UAVCAN
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
GPS2:/dev/ttyS2
|
||||
TEL2:/dev/ttyS3
|
||||
# CONSOLE: /dev/ttyS4
|
||||
# RC: /dev/ttyS5
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
mkblctrl
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
# uavcan - No H7 or FD can support in UAVCAN yet
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
|
@ -0,0 +1,13 @@
|
|||
{
|
||||
"board_id": 1009,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the CUAV Nora board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "NOra",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 1966080,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
|
@ -0,0 +1,41 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
#
|
||||
# Bootloader upgrade
|
||||
#
|
||||
set BL_FILE /etc/extras/cuav_nora_bootloader.bin
|
||||
if [ -f $BL_FILE ]
|
||||
then
|
||||
if param compare SYS_BL_UPDATE 1
|
||||
then
|
||||
param set SYS_BL_UPDATE 0
|
||||
param save
|
||||
echo "BL update..." >> $LOG_FILE
|
||||
bl_update $BL_FILE
|
||||
echo "BL update done" >> $LOG_FILE
|
||||
reboot
|
||||
fi
|
||||
fi
|
||||
unset BL_FILE
|
||||
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_V_DIV 18
|
||||
param set BAT1_V_DIV 18
|
||||
param set BAT2_V_DIV 18
|
||||
|
||||
param set BAT_A_PER_V 24
|
||||
param set BAT1_A_PER_V 24
|
||||
param set BAT2_A_PER_V 24
|
||||
|
||||
# Enable IMU thermal control
|
||||
param set SENS_EN_THERMAL 1
|
||||
fi
|
||||
|
||||
set LOGGER_BUF 64
|
||||
|
||||
rgbled_pwm start
|
||||
safety_button start
|
|
@ -0,0 +1,7 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific specific board MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
mavlink start -d /dev/ttyACM0
|
|
@ -0,0 +1,18 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# board specific sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
adc start
|
||||
|
||||
# SPI1 (internal)
|
||||
rm3100 -s start
|
||||
icm20689 -s -R 2 start
|
||||
|
||||
# SPI4 (internal)
|
||||
bmi088 -A -s -R 10 start
|
||||
bmi088 -G -s -R 10 start
|
||||
ms5611 -s -b 4 start
|
||||
|
||||
# SPI6 (internal)
|
||||
icm20649 -s -b 6 -R 2 start
|
||||
ms5611 -s -b 6 start
|
|
@ -0,0 +1,102 @@
|
|||
#
|
||||
# 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_STM32H743ZI=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=0x004c
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 BL CUAV Nora"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x3163
|
||||
CONFIG_CDCACM_VENDORSTR="CUAV"
|
||||
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_FS_WRITABLE=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_MAX_TASKS=8
|
||||
CONFIG_MAX_WDOGPARMS=2
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MM_REGIONS=3
|
||||
CONFIG_NFILE_DESCRIPTORS=5
|
||||
CONFIG_NFILE_STREAMS=3
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PREALLOC_WDOGS=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_USART6=y
|
||||
CONFIG_SYSTEMTICK_HOOK=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TIME_EXTENDED=y
|
||||
CONFIG_TTY_SIGINT=y
|
||||
CONFIG_TTY_SIGINT_CHAR=0x03
|
||||
CONFIG_TTY_SIGSTP=y
|
||||
CONFIG_USART6_DMA=y
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_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,281 @@
|
|||
/************************************************************************************
|
||||
* nuttx-config/include/board.h
|
||||
*
|
||||
* Copyright (C) 2020 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#include "board_dma_map.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdmmc.h"
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The board provides the following clock sources:
|
||||
*
|
||||
* X1: 16 MHz crystal for HSE
|
||||
*
|
||||
* So we have these clock source available within the STM32
|
||||
*
|
||||
* HSI: 16 MHz RC factory-trimmed
|
||||
* HSE: 16 MHz crystal for HSE
|
||||
*/
|
||||
#define STM32_BOARD_XTAL 16000000ul
|
||||
|
||||
#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 = 16,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_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE
|
||||
|
||||
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
|
||||
*
|
||||
* PLL1_VCO = (16,000,000 / 1) * 60 = 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(60)
|
||||
#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) * 60)
|
||||
#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(4)
|
||||
#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 / 4) * 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(4)
|
||||
#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 / 4) * 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
|
||||
*/
|
||||
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI /* I2C4 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */
|
||||
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 /* SPI6 clock source */
|
||||
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 /* USB 1 and 2 clock source */
|
||||
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */
|
||||
|
||||
/* FLASH wait states */
|
||||
#define BOARD_FLASH_WAITSTATES 2
|
||||
|
||||
/* SDMMC definitions ********************************************************/
|
||||
/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */
|
||||
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
|
||||
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
|
||||
*/
|
||||
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
|
||||
|
||||
/* UART/USART */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */
|
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
|
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_2 /* PG9 */
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */
|
||||
#define GPIO_USART6_RTS GPIO_USART6_RTS_2 /* PG8 */
|
||||
#define GPIO_USART6_CTS GPIO_USART6_CTS_NSS_2 /* PG15 */
|
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
|
||||
/* CAN */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PI9 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_4 /* PH13 */
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
|
||||
|
||||
/* SPI */
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_3 /* PG11 */
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
|
||||
|
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_6 /* PI1 */
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */
|
||||
|
||||
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_2 /* PE2 */
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
|
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
|
||||
|
||||
#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1 /* PF7 */
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
|
||||
|
||||
#define GPIO_SPI6_SCK GPIO_SPI6_SCK_1 /* PG13 */
|
||||
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
|
||||
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_2 /* PA7 */
|
||||
|
||||
/* I2C */
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
|
||||
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */
|
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */
|
||||
|
||||
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */
|
||||
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
|
||||
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
|
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
|
|
@ -0,0 +1,49 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
// DMAMUX1
|
||||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
|
||||
|
||||
#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_0 /* DMA1:81 */
|
||||
#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_0 /* DMA1:82 */
|
||||
|
||||
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_0 /* DMA1:83 */
|
||||
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4RX_1 /* DMA1:84 */
|
||||
|
||||
|
||||
// DMAMUX2 (BDMA)
|
||||
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* DMAMUX2:11 */
|
||||
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* DMAMUX2:12 */
|
|
@ -0,0 +1,245 @@
|
|||
#
|
||||
# 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_STM32H743ZI=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_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=0x004c
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 CUAV Nora"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x3163
|
||||
CONFIG_CDCACM_VENDORSTR="CUAV"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MAX_TASKS=64
|
||||
CONFIG_MAX_WDOGPARMS=2
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_MULTIBLOCK_DISABLE=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||
CONFIG_MM_REGIONS=3
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_PROGMEM=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NFILE_DESCRIPTORS=15
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_IFCONFIG=y
|
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PREALLOC_WDOGS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDMMC1_SDIO_MODE=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_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_BBSRAM=y
|
||||
CONFIG_STM32H7_BBSRAM_FILES=5
|
||||
CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_DTCMEXCLUDE=y
|
||||
CONFIG_STM32H7_DTCM_PROCFS=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C2=y
|
||||
CONFIG_STM32H7_I2C3=y
|
||||
CONFIG_STM32H7_I2C4=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC1=y
|
||||
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_SPI1=y
|
||||
CONFIG_STM32H7_SPI1_DMA=y
|
||||
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI4=y
|
||||
CONFIG_STM32H7_SPI5=y
|
||||
CONFIG_STM32H7_SPI6=y
|
||||
CONFIG_STM32H7_SPI6_DMA=y
|
||||
CONFIG_STM32H7_SPI6_DMA_BUFFER=512
|
||||
CONFIG_STM32H7_SPI_DMA=y
|
||||
CONFIG_STM32H7_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32H7_TIM12=y
|
||||
CONFIG_STM32H7_TIM15=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM3=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_USART6=y
|
||||
CONFIG_STM32H7_USART_BREAKS=y
|
||||
CONFIG_STM32H7_USART_INVERT=y
|
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32H7_USART_SWAP=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TIME_EXTENDED=y
|
||||
CONFIG_TTY_SIGINT=y
|
||||
CONFIG_TTY_SIGSTP=y
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_SERIAL_CONSOLE=y
|
||||
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_TXBUFSIZE=1500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_TXBUFSIZE=1500
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_IFLOWCONTROL=y
|
||||
CONFIG_USART6_OFLOWCONTROL=y
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
|
@ -0,0 +1,228 @@
|
|||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2020 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 board uses an STM32H743XIH6 and 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
|
||||
*
|
||||
* There's a switch on board, the BOOT0 pin is at ground so by default,
|
||||
* the STM32 will boot to address 0x0800:0000 in FLASH unless the switch 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
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 2048K
|
||||
DTCM1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
DTCM2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
|
||||
|
||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
|
||||
SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */
|
||||
SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */
|
||||
SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */
|
||||
SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */
|
||||
BKPRAM (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(.);
|
||||
|
||||
/*
|
||||
* This is a hack to make the newlib libm __errno() call
|
||||
* use the NuttX get_errno_ptr() function.
|
||||
*/
|
||||
__errno = get_errno_ptr;
|
||||
} > 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(.);
|
||||
} > AXI_SRAM AT > FLASH
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > AXI_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) }
|
||||
|
||||
.ramfunc : {
|
||||
_sramfuncs = .;
|
||||
*(.ramfunc .ramfunc.*)
|
||||
. = ALIGN(4);
|
||||
_eramfuncs = .;
|
||||
} > ITCM_RAM AT > FLASH
|
||||
|
||||
_framfuncs = LOADADDR(.ramfunc);
|
||||
}
|
|
@ -0,0 +1,226 @@
|
|||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2020 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 board uses an STM32H743XIH6 and 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
|
||||
*
|
||||
* There's a switch on board, the BOOT0 pin is at ground so by default,
|
||||
* the STM32 will boot to address 0x0800:0000 in FLASH unless the switch 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_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
|
||||
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
|
||||
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
|
||||
SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */
|
||||
SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */
|
||||
SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */
|
||||
SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */
|
||||
BKPRAM (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(.);
|
||||
|
||||
/*
|
||||
* This is a hack to make the newlib libm __errno() call
|
||||
* use the NuttX get_errno_ptr() function.
|
||||
*/
|
||||
__errno = get_errno_ptr;
|
||||
} > FLASH
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > FLASH
|
||||
|
||||
/*
|
||||
* Construction data for parameters.
|
||||
*/
|
||||
__param ALIGN(4): {
|
||||
__param_start = ABSOLUTE(.);
|
||||
KEEP(*(__param*))
|
||||
__param_end = 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(.);
|
||||
} > AXI_SRAM AT > FLASH
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > AXI_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,66 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
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)
|
||||
|
||||
else()
|
||||
add_library(drivers_board
|
||||
i2c.cpp
|
||||
init.c
|
||||
led.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,248 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file board_config.h
|
||||
*
|
||||
* Board internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
/* LEDs */
|
||||
#define GPIO_nLED_RED /* PI5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
|
||||
#define GPIO_nLED_GREEN /* PI6 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN6)
|
||||
#define GPIO_nLED_BLUE /* PI7 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN7)
|
||||
|
||||
#define BOARD_HAS_LED_PWM 1
|
||||
|
||||
/* ADC channels */
|
||||
#define PX4_ADC_GPIO \
|
||||
/* PA0 */ GPIO_ADC1_INP16, \
|
||||
/* PA1 */ GPIO_ADC1_INP17, \
|
||||
/* PA2 */ GPIO_ADC12_INP14, \
|
||||
/* PF11 */ GPIO_ADC1_INP2, \
|
||||
/* PC4 */ GPIO_ADC12_INP4, \
|
||||
/* PA4 */ GPIO_ADC12_INP18, \
|
||||
/* PF12 */ GPIO_ADC1_INP6, \
|
||||
/* PC5 */ GPIO_ADC12_INP8, \
|
||||
/* PC1 */ GPIO_ADC123_INP11, \
|
||||
/* PC2 */ GPIO_ADC123_INP12, \
|
||||
/* PC3 */ GPIO_ADC12_INP13
|
||||
|
||||
/* Define Channel numbers must match above GPIO pins */
|
||||
#define ADC_BATTERY1_VOLTAGE_CHANNEL 16 /* PA0 */
|
||||
#define ADC_BATTERY1_CURRENT_CHANNEL 17 /* PA1 */
|
||||
#define ADC_BATTERY2_VOLTAGE_CHANNEL 14 /* PA2 */
|
||||
#define ADC_BATTERY2_CURRENT_CHANNEL 2 /* PF11 */
|
||||
#define ADC1_6V6_IN_CHANNEL 4 /* PC4 */ // SPARE1_ADC1: ADC6.6
|
||||
#define ADC1_3V3_IN_CHANNEL 18 /* PA4 */ // SPARE2_ADC1: ADC3.3
|
||||
#define ADC_RSSI_IN_CHANNEL 6 /* PF12 */
|
||||
#define ADC_SCALED_V5_CHANNEL 8 /* PC5 */ // VDD_5V_SENS: Motherboard 5V voltage detection
|
||||
#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL 11 /* PC1 */ // SCALED_V3V3: Sensor power detection
|
||||
#define ADC_HW_VER_SENSE_CHANNEL 12 /* PC2 */
|
||||
#define ADC_HW_REV_SENSE_CHANNEL 13 /* PC3 */
|
||||
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
|
||||
(1 << ADC1_6V6_IN_CHANNEL) | \
|
||||
(1 << ADC1_3V3_IN_CHANNEL) | \
|
||||
(1 << ADC_RSSI_IN_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
|
||||
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
|
||||
(1 << ADC_HW_REV_SENSE_CHANNEL))
|
||||
|
||||
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
|
||||
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
|
||||
|
||||
#define GPIO_HW_REV_DRIVE /* PH14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN14)
|
||||
#define GPIO_HW_REV_SENSE /* PC3 */ GPIO_ADC12_INP13
|
||||
#define GPIO_HW_VER_DRIVE /* PH14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN3)
|
||||
#define GPIO_HW_VER_SENSE /* PC2 */ GPIO_ADC123_INP12
|
||||
|
||||
/* CAN Silence Silent mode control */
|
||||
#define GPIO_CAN1_SILENT_S0 /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2)
|
||||
#define GPIO_CAN2_SILENT_S1 /* PH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN3)
|
||||
|
||||
/* HEATER */
|
||||
#define GPIO_HEATER_OUTPUT /* PA8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
|
||||
|
||||
/* PWM */
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
#define BOARD_NUMBER_BRICKS 2
|
||||
|
||||
#define GPIO_nPOWER_IN_ADC /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1)
|
||||
#define GPIO_nPOWER_IN_CAN /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2)
|
||||
#define GPIO_nPOWER_IN_C /* PG0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN0)
|
||||
|
||||
#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_CAN /* Brick 1 is Chosen */
|
||||
#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_ADC /* Brick 2 is Chosen */
|
||||
#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB is Chosen */
|
||||
|
||||
#define GPIO_VDD_5V_HIPOWER_EN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11)
|
||||
#define GPIO_nVDD_5V_PERIPH_EN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4)
|
||||
#define GPIO_VDD_5V_RC_EN /* PG5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN5)
|
||||
#define GPIO_VDD_3V3_SD_CARD_EN /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN7)
|
||||
|
||||
#define GPIO_VDD_5V_HIPOWER_OC /* PJ3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN3)
|
||||
#define GPIO_nVDD_5V_PERIPH_OC /* PJ4 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN4)
|
||||
|
||||
/* Power switch controls ******************************************************/
|
||||
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, !(on_true))
|
||||
#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_EN, (on_true))
|
||||
#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true))
|
||||
|
||||
#define SPEKTRUM_POWER(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_RC_EN, (on_true))
|
||||
#define READ_SPEKTRUM_POWER() px4_arch_gpioread(GPIO_VDD_5V_RC_EN)
|
||||
|
||||
/* Tone alarm output */
|
||||
#define TONE_ALARM_TIMER 15 /* timer 15 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* PE5 TIM15_CH1 */
|
||||
|
||||
#define GPIO_TONE_ALARM_IDLE /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN5) // ALARM
|
||||
#define GPIO_TONE_ALARM GPIO_TIM15_CH1OUT_2
|
||||
|
||||
/* USB
|
||||
* OTG FS: PA9 OTG_FS_VBUS VBUS sensing
|
||||
* HS USB EN: PH15
|
||||
*/
|
||||
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
#define GPIO_HS_USB_EN /* PH15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN15)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 3 /* use timer3 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
|
||||
#define STM32_RCC_APB1ENR STM32_RCC_APB1LENR
|
||||
#define RCC_APB1ENR_TIM3EN RCC_APB1LENR_TIM3EN
|
||||
|
||||
#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */
|
||||
#define GPIO_PPM_IN /* PB4 T3C1 */ GPIO_TIM3_CH1IN_2
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
/**
|
||||
* GPIO PPM_IN on PB4 T3C1
|
||||
* SPEKTRUM_RX (it's TX or RX in Bind) on UART8 PE0
|
||||
* Inversion is possible in the UART and can drive GPIO_PPM_IN as an output
|
||||
*/
|
||||
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
|
||||
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
|
||||
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
|
||||
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
|
||||
|
||||
/* RSSI_IN */
|
||||
#define GPIO_RSSI_IN /* PB0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
|
||||
|
||||
/* Safety Switch is only on FMU */
|
||||
#define FMU_LED_AMBER /* PE12 */ (GPIO_OUTPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN12) // FMU_LED_AMBER
|
||||
#define GPIO_BTN_SAFETY /* PE10 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN10) // SAFETY_SW
|
||||
|
||||
#define GPIO_LED_SAFETY FMU_LED_AMBER
|
||||
|
||||
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
|
||||
* this board support the ADC system_power interface, and therefore
|
||||
* provides the true logic GPIO BOARD_ADC_xxxx macros.
|
||||
*/
|
||||
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS))
|
||||
#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID))
|
||||
#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
|
||||
#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
|
||||
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_PERIPH_OC))
|
||||
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_OC))
|
||||
|
||||
|
||||
/* 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 BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
|
||||
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4};
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
PX4_ADC_GPIO, \
|
||||
GPIO_HW_REV_DRIVE, \
|
||||
GPIO_HW_VER_DRIVE, \
|
||||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN2_TX, \
|
||||
GPIO_CAN2_RX, \
|
||||
GPIO_CAN1_SILENT_S0, \
|
||||
GPIO_CAN2_SILENT_S1, \
|
||||
GPIO_HEATER_OUTPUT, \
|
||||
GPIO_nPOWER_IN_CAN, \
|
||||
GPIO_nPOWER_IN_ADC, \
|
||||
GPIO_nPOWER_IN_C, \
|
||||
GPIO_nVDD_5V_PERIPH_EN, \
|
||||
GPIO_nVDD_5V_PERIPH_OC, \
|
||||
GPIO_VDD_5V_HIPOWER_EN, \
|
||||
GPIO_VDD_5V_HIPOWER_OC, \
|
||||
GPIO_VDD_5V_RC_EN, \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),\
|
||||
GPIO_VDD_3V3_SD_CARD_EN, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_OTGFS_VBUS, \
|
||||
PX4_GPIO_PIN_OFF(GPIO_HS_USB_EN), \
|
||||
GPIO_RSSI_IN, \
|
||||
FMU_LED_AMBER, \
|
||||
GPIO_BTN_SAFETY, \
|
||||
}
|
||||
|
||||
__BEGIN_DECLS
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
extern void board_peripheral_reset(int ms);
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
#endif /* __ASSEMBLY__ */
|
||||
__END_DECLS
|
|
@ -0,0 +1,74 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file 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 "up_internal.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_configgpio(GPIO_OTGFS_VBUS);
|
||||
}
|
||||
|
||||
__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 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************
|
||||
* 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/ttyS4,57600"
|
||||
#define BOOT_DELAY_ADDRESS 0x000001a0
|
||||
#define BOARD_TYPE 1009
|
||||
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
|
||||
#define BOARD_FLASH_SECTORS (15)
|
||||
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)
|
||||
|
||||
#define OSC_FREQ 16
|
||||
|
||||
#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,41 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusExternal(1),
|
||||
initI2CBusExternal(2),
|
||||
initI2CBusInternal(3),
|
||||
initI2CBusExternal(4),
|
||||
};
|
|
@ -0,0 +1,213 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file 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 <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
#include <arch/board/board.h>
|
||||
#include "up_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)
|
||||
{
|
||||
/* set the peripheral rails off */
|
||||
VDD_5V_PERIPH_EN(false);
|
||||
board_control_spi_sensors_power(false, 0xffff);
|
||||
|
||||
bool last = READ_SPEKTRUM_POWER();
|
||||
/* Keep Spektum on to discharge rail*/
|
||||
SPEKTRUM_POWER(false);
|
||||
|
||||
/* wait for the peripheral rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
/* switch the peripheral rail back on */
|
||||
SPEKTRUM_POWER(last);
|
||||
board_control_spi_sensors_power(true, 0xffff);
|
||||
VDD_5V_PERIPH_EN(true);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* 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));
|
||||
|
||||
board_control_spi_sensors_power_configgpio();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* 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)
|
||||
{
|
||||
/* Power on Interfaces */
|
||||
VDD_5V_PERIPH_EN(true);
|
||||
VDD_5V_HIPOWER_EN(true);
|
||||
board_control_spi_sensors_power(true, 0xffff);
|
||||
SPEKTRUM_POWER(true);
|
||||
|
||||
/* Need hrt running before using the ADC */
|
||||
px4_platform_init();
|
||||
|
||||
/* configure SPI interfaces (after we determined the HW version) */
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* 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_on(LED_GREEN); // Indicate Power.
|
||||
led_off(LED_BLUE);
|
||||
|
||||
if (board_hardfault_init(2, true) != 0) {
|
||||
led_on(LED_RED);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
// Ensure Power is off for > 10 mS
|
||||
usleep(15 * 1000);
|
||||
VDD_3V3_SD_CARD_EN(true);
|
||||
usleep(500 * 1000);
|
||||
|
||||
/* Mount the SDIO-based MMC/SD block driver */
|
||||
/* First, get an instance of the SDIO interface */
|
||||
struct sdio_dev_s *sdio_dev = sdio_initialize(0); // SDIO_SLOTNO 0 Only one slot
|
||||
|
||||
if (!sdio_dev) {
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (mmcsd_slotinitialize(0, sdio_dev) != OK) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Assume that the SD card is inserted. What choice do we have? */
|
||||
sdio_mediachange(sdio_dev, true);
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -0,0 +1,111 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file 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 up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
# define xlat(p) (p)
|
||||
static uint32_t g_ledmap[] = {
|
||||
FMU_LED_AMBER, // Indexed by LED_SAFETY (defaulted to an output)
|
||||
};
|
||||
|
||||
__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,64 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/spi_hw_description.h>
|
||||
#include <drivers/drv_sensor.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortF, GPIO::Pin10}, SPI::DRDY{GPIO::PortE, GPIO::Pin7}), // ADIS16470
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortG, GPIO::Pin6}, SPI::DRDY{GPIO::PortJ, GPIO::Pin0}),
|
||||
}, {GPIO::PortE, GPIO::Pin3}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortF, GPIO::Pin5}),
|
||||
initSPIDevice(DRV_MAG_DEVTYPE_RM3100, SPI::CS{GPIO::PortF, GPIO::Pin2}, SPI::DRDY{GPIO::PortE, GPIO::Pin4}),
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI4, {
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin3}, SPI::DRDY{GPIO::PortB, GPIO::Pin15}),
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin4}, SPI::DRDY{GPIO::PortB, GPIO::Pin14}),
|
||||
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortG, GPIO::Pin10}),
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI5, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin4}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin13}),
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI6, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin12}, SPI::DRDY{GPIO::PortH, GPIO::Pin5}),
|
||||
//initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin12}),
|
||||
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortI, GPIO::Pin8}),
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
|
@ -0,0 +1,88 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer5, DMA{DMA::Index1}),
|
||||
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
|
||||
// initIOTimer(Timer::Timer1, DMA{DMA::Index1}),
|
||||
// initIOTimer(Timer::Timer12, DMA{DMA::Index1}),
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
// MAIN
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}),
|
||||
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}),
|
||||
|
||||
// AUX
|
||||
// initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}),
|
||||
// initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}),
|
||||
// initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortA, GPIO::Pin10}),
|
||||
// initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}),
|
||||
// initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}),
|
||||
// initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}),
|
||||
};
|
||||
|
||||
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::Timer8),
|
||||
};
|
||||
|
||||
#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::Timer8, Timer::Channel1}, {GPIO::PortI, GPIO::Pin5}, 1),
|
||||
initIOTimerChannelLED(led_pwm_timers, {Timer::Timer8, Timer::Channel2}, {GPIO::PortI, GPIO::Pin6}, 2),
|
||||
initIOTimerChannelLED(led_pwm_timers, {Timer::Timer8, Timer::Channel3}, {GPIO::PortI, GPIO::Pin7}, 3),
|
||||
};
|
|
@ -0,0 +1,58 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file 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>
|
||||
|
||||
/************************************************************************************
|
||||
* 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