forked from Archive/PX4-Autopilot
Initial Hex/Proficnc Cube Yellow support
This commit is contained in:
parent
ee32ded222
commit
cf02b88d51
|
@ -34,6 +34,7 @@ pipeline {
|
|||
"bitcraze_crazyflie_default",
|
||||
"cuav_x7pro_default",
|
||||
"hex_cube-orange_default",
|
||||
"hex_cube-yellow_default",
|
||||
"holybro_durandal-v1_default",
|
||||
"holybro_durandal-v1_stackcheck",
|
||||
"holybro_kakutef7",
|
||||
|
|
|
@ -20,6 +20,7 @@ jobs:
|
|||
bitcraze_crazyflie_default,
|
||||
cuav_x7pro_default,
|
||||
hex_cube-orange_default,
|
||||
hex_cube-yellow_default,
|
||||
holybro_durandal-v1_default,
|
||||
holybro_durandal-v1_stackcheck,
|
||||
holybro_kakutef7_default,
|
||||
|
|
|
@ -71,6 +71,11 @@ CONFIG:
|
|||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: hex_cube-orange_default
|
||||
hex_cube-yellow_default:
|
||||
short: hex_cube-yellow
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: hex_cube-yellow_default
|
||||
holybro_durandal-v1_default:
|
||||
short: holybro_durandal-v1
|
||||
buildType: MinSizeRel
|
||||
|
|
|
@ -0,0 +1,130 @@
|
|||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR hex
|
||||
MODEL cube-yellow
|
||||
LABEL default
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 1
|
||||
SERIAL_PORTS
|
||||
# IO DEBUG:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
GPS1:/dev/ttyS3
|
||||
GPS2:/dev/ttyS4
|
||||
# CONSOLE:/dev/tty5
|
||||
# PX4IO:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20948
|
||||
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
|
||||
px4io
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
#safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
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
|
||||
#micrortps_bridge
|
||||
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": 120,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the Hex Cube Yellow board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "CubeYellow",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 2064384,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
|
@ -0,0 +1,21 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
param set BAT_V_DIV 10.1
|
||||
param set BAT1_V_DIV 10.1
|
||||
param set BAT2_V_DI 10.1
|
||||
|
||||
param set BAT_A_PER_V 17
|
||||
param set BAT1_A_PER_V 17
|
||||
param set BAT2_A_PER_V 17
|
||||
|
||||
# Disable IMU thermal control by FMU
|
||||
param set SENS_EN_THERMAL -1
|
||||
fi
|
||||
|
||||
set LOGGER_BUF 64
|
|
@ -0,0 +1,7 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
mavlink start -d /dev/ttyACM0
|
|
@ -0,0 +1,20 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
adc start
|
||||
|
||||
# SPI1
|
||||
ms5611 -s -b 1 start
|
||||
icm20649 -s -b 1 start
|
||||
|
||||
# SPI4
|
||||
ms5611 -s -b 4 start
|
||||
icm20602 -s -b 4 -R 12 start
|
||||
icm20948 -s -b 4 -R 10 -M start
|
||||
|
||||
# Possible external compasses
|
||||
ist8310 -X start
|
||||
hmc5883 -T -X start
|
||||
qmc5883 -X start
|
||||
lis3mdl -X start
|
|
@ -0,0 +1,17 @@
|
|||
#
|
||||
# For a description of the syntax of this configuration file,
|
||||
# see misc/tools/kconfig-language.txt.
|
||||
#
|
||||
config BOARD_HAS_PROBES
|
||||
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
|
||||
default y
|
||||
---help---
|
||||
This board provides GPIO FMU-CH1-6 as PROBE_1-6 to provide timing signals from selected drivers.
|
||||
|
||||
config BOARD_USE_PROBES
|
||||
bool "Enable the use the board provided FMU-CH1-6 as PROBE_1-6"
|
||||
default n
|
||||
depends on BOARD_HAS_PROBES
|
||||
|
||||
---help---
|
||||
Select to use GPIO FMU-CH1-6 to provide timing signals from selected drivers.
|
|
@ -0,0 +1,424 @@
|
|||
/************************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
|
||||
* Authors: David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifndef __NUTTX_CONFIG_HEX_CUBE_YELLOW_INCLUDE_BOARD_H
|
||||
#define __NUTTX_CONFIG_HEX_CUBE_YELLOW_INCLUDE_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
#include "board_dma_map.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdmmc.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The Cube Yellow board provides the following clock sources:
|
||||
*
|
||||
* X301: 24 MHz crystal for HSE
|
||||
*
|
||||
* So we have these clock source available within the STM32
|
||||
*
|
||||
* HSI: 16 MHz RC factory-trimmed
|
||||
* HSE: 24 MHz crystal for HSE
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_XTAL 24000000ul
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
#define STM32_LSE_FREQUENCY 0
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
* PLL source is HSE = 24,000,000
|
||||
*
|
||||
* PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
|
||||
* Subject to:
|
||||
*
|
||||
* 2 <= PLLM <= 63
|
||||
* 192 <= PLLN <= 432
|
||||
* 192 MHz <= PLL_VCO <= 432MHz
|
||||
*
|
||||
* SYSCLK = PLL_VCO / PLLP
|
||||
* Subject to
|
||||
*
|
||||
* PLLP = {2, 4, 6, 8}
|
||||
* SYSCLK <= 216 MHz
|
||||
*
|
||||
* USB OTG FS, SDMMC and RNG Clock = PLL_VCO / PLLQ
|
||||
* Subject to
|
||||
* The USB OTG FS requires a 48 MHz clock to work correctly. The SDMMC
|
||||
* and the random number generator need a frequency lower than or equal
|
||||
* to 48 MHz to work correctly.
|
||||
*
|
||||
* 2 <= PLLQ <= 15
|
||||
*/
|
||||
|
||||
/* Highest SYSCLK with USB OTG FS clock = 48 MHz
|
||||
*
|
||||
* PLL_VCO = (24,000,000 / 12) * 216 = 432 MHz
|
||||
* SYSCLK = 432 MHz / 2 = 216 MHz
|
||||
* USB OTG FS, SDMMC and RNG Clock = 432 MHz / 9 = 48 MHz
|
||||
*/
|
||||
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(12)
|
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(216)
|
||||
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
|
||||
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(9)
|
||||
|
||||
#define STM32_VCO_FREQUENCY ((STM32_HSE_FREQUENCY / 12) * 216)
|
||||
#define STM32_SYSCLK_FREQUENCY (STM32_VCO_FREQUENCY / 2)
|
||||
#define STM32_OTGFS_FREQUENCY (STM32_VCO_FREQUENCY / 9)
|
||||
|
||||
/* Configure factors for PLLSAI clock */
|
||||
|
||||
#define CONFIG_STM32F7_PLLSAI 1
|
||||
#define STM32_RCC_PLLSAICFGR_PLLSAIN RCC_PLLSAICFGR_PLLSAIN(192)
|
||||
#define STM32_RCC_PLLSAICFGR_PLLSAIP RCC_PLLSAICFGR_PLLSAIP(8)
|
||||
#define STM32_RCC_PLLSAICFGR_PLLSAIQ RCC_PLLSAICFGR_PLLSAIQ(4)
|
||||
#define STM32_RCC_PLLSAICFGR_PLLSAIR RCC_PLLSAICFGR_PLLSAIR(2)
|
||||
|
||||
/* Configure Dedicated Clock Configuration Register */
|
||||
|
||||
#define STM32_RCC_DCKCFGR1_PLLI2SDIVQ RCC_DCKCFGR1_PLLI2SDIVQ(1)
|
||||
#define STM32_RCC_DCKCFGR1_PLLSAIDIVQ RCC_DCKCFGR1_PLLSAIDIVQ(1)
|
||||
#define STM32_RCC_DCKCFGR1_PLLSAIDIVR RCC_DCKCFGR1_PLLSAIDIVR(0)
|
||||
#define STM32_RCC_DCKCFGR1_SAI1SRC RCC_DCKCFGR1_SAI1SEL(0)
|
||||
#define STM32_RCC_DCKCFGR1_SAI2SRC RCC_DCKCFGR1_SAI2SEL(0)
|
||||
#define STM32_RCC_DCKCFGR1_TIMPRESRC 0
|
||||
#define STM32_RCC_DCKCFGR1_DFSDM1SRC 0
|
||||
#define STM32_RCC_DCKCFGR1_ADFSDM1SRC 0
|
||||
|
||||
|
||||
|
||||
/* Configure factors for PLLI2S clock */
|
||||
|
||||
#define CONFIG_STM32F7_PLLI2S 1
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192)
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SP RCC_PLLI2SCFGR_PLLI2SP(2)
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2)
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
|
||||
|
||||
/* Configure Dedicated Clock Configuration Register 2 */
|
||||
|
||||
#define STM32_RCC_DCKCFGR2_USART1SRC RCC_DCKCFGR2_USART1SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_USART2SRC RCC_DCKCFGR2_USART2SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_UART4SRC RCC_DCKCFGR2_UART4SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_UART5SRC RCC_DCKCFGR2_UART5SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_USART6SRC RCC_DCKCFGR2_USART6SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_UART7SRC RCC_DCKCFGR2_UART7SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_UART8SRC RCC_DCKCFGR2_UART8SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_I2C1SRC RCC_DCKCFGR2_I2C1SEL_HSI
|
||||
#define STM32_RCC_DCKCFGR2_I2C2SRC RCC_DCKCFGR2_I2C2SEL_HSI
|
||||
#define STM32_RCC_DCKCFGR2_I2C3SRC RCC_DCKCFGR2_I2C3SEL_HSI
|
||||
#define STM32_RCC_DCKCFGR2_I2C4SRC RCC_DCKCFGR2_I2C4SEL_HSI
|
||||
#define STM32_RCC_DCKCFGR2_LPTIM1SRC RCC_DCKCFGR2_LPTIM1SEL_APB
|
||||
#define STM32_RCC_DCKCFGR2_CECSRC RCC_DCKCFGR2_CECSEL_HSI
|
||||
#define STM32_RCC_DCKCFGR2_CK48MSRC RCC_DCKCFGR2_CK48MSEL_PLL
|
||||
#define STM32_RCC_DCKCFGR2_SDMMCSRC RCC_DCKCFGR2_SDMMCSEL_48MHZ
|
||||
#define STM32_RCC_DCKCFGR2_SDMMC2SRC RCC_DCKCFGR2_SDMMC2SEL_48MHZ
|
||||
#define STM32_RCC_DCKCFGR2_DSISRC RCC_DCKCFGR2_DSISEL_PHY
|
||||
|
||||
|
||||
/* Several prescalers allow the configuration of the two AHB buses, the
|
||||
* high-speed APB (APB2) and the low-speed APB (APB1) domains. The maximum
|
||||
* frequency of the two AHB buses is 216 MHz while the maximum frequency of
|
||||
* the high-speed APB domains is 108 MHz. The maximum allowed frequency of
|
||||
* the low-speed APB domain is 54 MHz.
|
||||
*/
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK (216 MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
|
||||
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
|
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
|
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/4 (54 MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
|
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
|
||||
|
||||
/* 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)
|
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (108MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
|
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* 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_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* SDMMC dividers. Note that slower clocking is required when DMA is disabled
|
||||
* in order to avoid RX overrun/TX underrun errors due to delayed responses
|
||||
* to service FIFOs in interrupt driven mode. These values have not been
|
||||
* tuned!!!
|
||||
*
|
||||
* SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(118+2)=400 KHz
|
||||
*/
|
||||
|
||||
/* Use the Falling edge of the SDIO_CLK clock to change the edge the
|
||||
* data and commands are change on
|
||||
*/
|
||||
|
||||
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
|
||||
|
||||
#define STM32_SDMMC_INIT_CLKDIV (118 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz
|
||||
* DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_STM32F7_SDMMC_DMA
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz
|
||||
* DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz
|
||||
*/
|
||||
//TODO #warning "Check Freq for 24mHz"
|
||||
|
||||
#ifdef CONFIG_STM32F7_SDMMC_DMA
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
/* FLASH wait states
|
||||
*
|
||||
* --------- ---------- -----------
|
||||
* VDD MAX SYSCLK WAIT STATES
|
||||
* --------- ---------- -----------
|
||||
* 1.7-2.1 V 180 MHz 8
|
||||
* 2.1-2.4 V 216 MHz 9
|
||||
* 2.4-2.7 V 216 MHz 8
|
||||
* 2.7-3.6 V 216 MHz 7
|
||||
* --------- ---------- -----------
|
||||
*/
|
||||
|
||||
#define BOARD_FLASH_WAITSTATES 7
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PB7 */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* 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_2 /* PD3 */
|
||||
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
|
||||
#define GPIO_USART3_CTS GPIO_USART3_CTS_2 /* PD11 */
|
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */
|
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
|
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_1 /* PE7 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */
|
||||
|
||||
/* USART8: has no remap
|
||||
*
|
||||
* GPIO_UART8_RX PE0[CN12-64]
|
||||
* GPIO_UART8_TX PE1[CN11-61]
|
||||
*/
|
||||
|
||||
/* CAN
|
||||
*
|
||||
* CAN1 is routed to transceiver.
|
||||
* CAN2 is routed to transceiver.
|
||||
*/
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_2 /* PB6 */
|
||||
|
||||
/* SPI
|
||||
*
|
||||
* SPI1 sensors
|
||||
* SPI2 is FRAM
|
||||
* SPI4 sesnors
|
||||
*/
|
||||
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /* PA5 */
|
||||
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */
|
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_3 /* PB13 */
|
||||
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE5 */
|
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE6 */
|
||||
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE2 */
|
||||
|
||||
/* I2C
|
||||
*
|
||||
* I2C1_SCL PB8
|
||||
* I2C1_SDA PB9
|
||||
* I2C2_SCL PB10
|
||||
* I2C2_SDA PB11
|
||||
*/
|
||||
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
|
||||
|
||||
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
|
||||
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
|
||||
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */
|
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */
|
||||
|
||||
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10)
|
||||
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11)
|
||||
|
||||
/* SDMMC1
|
||||
*
|
||||
* VDD 3.3
|
||||
* GND
|
||||
* SDMMC1_CK PC12
|
||||
* SDMMC1_CMD PD2
|
||||
* SDMMC1_D0 PC8
|
||||
* SDMMC1_D1 PC9
|
||||
* SDMMC1_D2 PC10
|
||||
* SDMMC1_D3 PC11
|
||||
*/
|
||||
|
||||
/* USB
|
||||
*
|
||||
* OTG_FS_DM PA11
|
||||
* OTG_FS_DP PA12
|
||||
* VBUS PA9
|
||||
*/
|
||||
|
||||
|
||||
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
|
||||
|
||||
#if defined(CONFIG_BOARD_USE_PROBES)
|
||||
# include "stm32_gpio.h"
|
||||
# define PROBE_N(n) (1<<((n)-1))
|
||||
# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14) /* PE14 AUX1 */
|
||||
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13) /* PE13 AUX2 */
|
||||
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 AUX3 */
|
||||
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) /* PE9 AUX4 */
|
||||
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */
|
||||
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */
|
||||
|
||||
# define PROBE_INIT(mask) \
|
||||
do { \
|
||||
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
|
||||
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
|
||||
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
|
||||
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
|
||||
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
|
||||
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
|
||||
} while(0)
|
||||
|
||||
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
|
||||
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
|
||||
#else
|
||||
# define PROBE_INIT(mask)
|
||||
# define PROBE(n,s)
|
||||
# define PROBE_MARK(n)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void stm32_boardinitialize(void);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /*__NUTTX_CONFIG_HEX_CUBE_YELLOW_INCLUDE_BOARD_H */
|
|
@ -0,0 +1,99 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
| DMA1 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 |
|
||||
|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|
|
||||
| Channel 0 | SPI3_RX_1 | SPDIFRX_DT | SPI3_RX_2 | SPI2_RX | SPI2_TX | SPI3_TX_1 | SPDIFRX_CS | SPI3_TX_2 |
|
||||
| Channel 1 | I2C1_RX | I2C3_RX | TIM7_UP_1 | - | TIM7_UP_2 | I2C1_RX_1 | I2C1_TX | I2C1_TX_1 |
|
||||
| Channel 2 | TIM4_CH1 | - | I2C4_RX | TIM4_CH2 | - | I2C4_RX | TIM4_UP | TIM4_CH3 |
|
||||
| Channel 3 | - | TIM2_UP_1 | I2C3_RX_1 | - | I2C3_TX | TIM2_CH1 | TIM2_CH2 | TIM2_UP_2 |
|
||||
| | | TIM2_CH3 | | | | | TIM2_CH4_1 | TIM2_CH4_2 |
|
||||
| Channel 4 | UART5_RX | USART3_RX | UART4_RX | USART3_TX_1 | UART4_TX | USART2_RX | USART2_TX | UART5_TX |
|
||||
| Channel 5 | UART8_TX | UART7_TX | TIM3_CH4 | UART7_RX | TIM3_CH1 | TIM3_CH2 | UART8_RX | TIM3_CH3 |
|
||||
| | | | TIM3_UP | | TIM3_TRIG | | | |
|
||||
| Channel 6 | TIM5_CH3 | TIM5_CH4_1 | TIM5_CH1 | TIM5_CH4_2 | TIM5_CH2 | - | TIM5_UP_2 | - |
|
||||
| | TIM5_UP_1 | TIM5_TRIG_1 | | TIM5_TRIG_2 | | | | |
|
||||
| Channel 7 | - | TIM6_UP | I2C2_RX | I2C2_RX_1 | USART3_TX_2 | DAC1 | DAC2 | I2C2_TX |
|
||||
| Channel 8 | I2C3_TX | I2C4_RX | - | - | I2C2_TX | - | I2C4_TX | - |
|
||||
| Channel 9 | - | SPI2_RX | - | - | - | - | SPI2_TX | - |
|
||||
| | | | | | | | | |
|
||||
| Usage | UART8_TX | USART3_RX | UART4_RX | USART3_TX_1 | | USART2_RX | UART8_RX | |
|
||||
|
||||
|
||||
| DMA2 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 |
|
||||
|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|
|
||||
| Channel 0 | ADC1_1 | SAI1_A | TIM8_CH1_1 | SAI1_A_1 | ADC1_2 | SAI1_B_1 | TIM1_CH1_1 | SAI2_B_2 |
|
||||
| | | | TIM8_CH2_1 | | | | TIM1_CH2_1 | |
|
||||
| | | | TIM8_CH3_1 | | | | TIM1_CH3_1 | |
|
||||
| Channel 1 | - | DCMI_1 | ADC2_1 | ADC2_2 | SAI1_B | SPI6_TX | SPI6_RX | DCMI_2 |
|
||||
| Channel 2 | ADC3_1 | ADC3_2 | - | SPI5_RX_1 | SPI5_TX_1 | CRYP_OUT | CRYP_IN | HASH_IN |
|
||||
| Channel 3 | SPI1_RX_1 | - | SPI1_RX_2 | SPI1_TX_1 | SAI2_A | SPI1_TX_2 | SAI2_B | QUADSPI |
|
||||
| Channel 4 | SPI4_RX_1 | SPI4_TX_1 | USART1_RX_1 | SDMMC1_1 | - | USART1_RX_2 | SDMMC1_2 | USART1_TX |
|
||||
| Channel 5 | - | USART6_RX_1 | USART6_RX_2 | SPI4_RX_2 | SPI4_TX_2 | - | USART6_TX_1 | USART6_TX_2 |
|
||||
| Channel 6 | TIM1_TRIG_1 | TIM1_CH1_2 | TIM1_CH2_2 | TIM1_CH1 | TIM1_CH4 | TIM1_UP | TIM1_CH3_2 | - |
|
||||
| | | | | | TIM1_TRIG_2 | | | |
|
||||
| | | | | | TIM1_COM | | | |
|
||||
| Channel 7 | - | TIM8_UP | TIM8_CH1_2 | TIM8_CH2_2 | TIM8_CH3_2 | SPI5_RX_2 | SPI5_TX_2 | TIM8_CH4 |
|
||||
| | | | | | | | | TIM8_TRIG |
|
||||
| | | | | | | | | TIM8_COM |
|
||||
| Channel 8 | DSFDM1_FLT0 | DSFDM1_FLT1 | DSFDM1_FLT2 | DSFDM1_FLT3 | DSFDM1_FLT0 | DSFDM1_FLT1 | DSFDM1_FLT2 | DSFDM1_FLT3 |
|
||||
| Channel 9 | JPEG_IN | JPEG_OUT | SPI4_TX | JPEG_IN | JPEG_OUT | SPI5_RX | - | - |
|
||||
| Channel 10 | SAI1_B | SAI2_B | SAI2_A | - | - | - | SAI1_A | - |
|
||||
| Channel 11 | SDMMC2 | - | QUADSPI | - | - | SDMMC2 | - | - |
|
||||
| | | | | | | | | |
|
||||
| Usage | SPI1_RX_1 | | USART6_RX_2 | SPI1_TX_1 | | TIM1_UP | SDMMC1_2 | USART6_TX_2 |
|
||||
*/
|
||||
|
||||
// DMA1 Channel/Stream Selections
|
||||
//--------------------------------------------//---------------------------//----------------
|
||||
// DMAMAP_UART8_TX // DMA1, Stream 0, Channel 5
|
||||
// DMAMAP_USART3_RX // DMA1, Stream 1, Channel 4
|
||||
// DMAMAP_UART4_RX // DMA1, Stream 2, Channel 4
|
||||
// DMAMAP_USART3_TX DMAMAP_USART3_TX_1 // DMA1, Stream 3, Channel 4
|
||||
// DMAMAP_USART2_RX // DMA1, Stream 5, Channel 4
|
||||
// DMAMAP_UART8_RX // DMA1, Stream 6, Channel 5
|
||||
|
||||
|
||||
// DMA2 Channel/Stream Selections
|
||||
//--------------------------------------------//---------------------------//----------------
|
||||
#define DMAMAP_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3 (MS5611, ICM20649)
|
||||
#define DMAMAP_SPI4_TX DMAMAP_SPI4_TX_1 // DMA2, Stream 1, Channel 4 (MS5611, ICM20602, ICM20948)
|
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 // DMA2, Stream 2, Channel 5 (PX4_IO RX)
|
||||
#define DMAMAP_SPI4_RX DMAMAP_SPI4_RX_2 // DMA2, Stream 3, Channel 3 (MS5611, ICM20602, ICM20948)
|
||||
// AVAILABLE // DMA2, Stream 4
|
||||
#define DMAMAP_SPI1_TX DMAMAP_SPI1_TX_2 // DMA2, Stream 5, Channel 3 (MS5611, ICM20649)
|
||||
#define DMAMAP_SDMMC1 DMAMAP_SDMMC1_2 // DMA2, Stream 6, Channel 4 (SDMMC)
|
||||
#define DMAMAP_USART6_TX DMAMAP_USART6_TX_2 // DMA2, Stream 7, Channel 5 (PX4_IO TX)
|
|
@ -0,0 +1,244 @@
|
|||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_OS_API is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_FS_PROCFS_EXCLUDE_ENVIRON 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="stm32f7"
|
||||
CONFIG_ARCH_CHIP_STM32F765II=y
|
||||
CONFIG_ARCH_CHIP_STM32F7=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=22114
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x1012
|
||||
CONFIG_CDCACM_PRODUCTSTR="CubeYellow"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x2DAE
|
||||
CONFIG_CDCACM_VENDORSTR="Hex/ProfiCNC"
|
||||
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_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_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_MQ_MSGS=4
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PREALLOC_WDOGS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDMMC1_SDIO_MODE=y
|
||||
CONFIG_SDMMC1_SDIO_PULLUP=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=256
|
||||
CONFIG_STM32F7_ADC1=y
|
||||
CONFIG_STM32F7_BBSRAM=y
|
||||
CONFIG_STM32F7_BBSRAM_FILES=5
|
||||
CONFIG_STM32F7_BKPSRAM=y
|
||||
CONFIG_STM32F7_DMA1=y
|
||||
CONFIG_STM32F7_DMA2=y
|
||||
CONFIG_STM32F7_DMACAPABLE=y
|
||||
CONFIG_STM32F7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32F7_I2C1=y
|
||||
CONFIG_STM32F7_I2C2=y
|
||||
CONFIG_STM32F7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32F7_OTGFS=y
|
||||
CONFIG_STM32F7_PROGMEM=y
|
||||
CONFIG_STM32F7_PWR=y
|
||||
CONFIG_STM32F7_RTC=y
|
||||
CONFIG_STM32F7_RTC_HSECLOCK=y
|
||||
CONFIG_STM32F7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32F7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32F7_SDMMC1=y
|
||||
CONFIG_STM32F7_SDMMC_DMA=y
|
||||
CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32F7_SPI1=y
|
||||
CONFIG_STM32F7_SPI1_DMA=y
|
||||
CONFIG_STM32F7_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32F7_SPI2=y
|
||||
CONFIG_STM32F7_SPI4=y
|
||||
CONFIG_STM32F7_SPI4_DMA=y
|
||||
CONFIG_STM32F7_SPI4_DMA_BUFFER=1024
|
||||
CONFIG_STM32F7_SPI_DMA=y
|
||||
CONFIG_STM32F7_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32F7_TIM10=y
|
||||
CONFIG_STM32F7_TIM11=y
|
||||
CONFIG_STM32F7_UART4=y
|
||||
CONFIG_STM32F7_UART7=y
|
||||
CONFIG_STM32F7_UART8=y
|
||||
CONFIG_STM32F7_USART1=y
|
||||
CONFIG_STM32F7_USART2=y
|
||||
CONFIG_STM32F7_USART3=y
|
||||
CONFIG_STM32F7_USART6=y
|
||||
CONFIG_STM32F7_USART_BREAKS=y
|
||||
CONFIG_STM32F7_USART_INVERT=y
|
||||
CONFIG_STM32F7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32F7_USART_SWAP=y
|
||||
CONFIG_STM32F7_WWDG=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TIME_EXTENDED=y
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_RXDMA=y
|
||||
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_RXDMA=y
|
||||
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_RXDMA=y
|
||||
CONFIG_USART2_TXBUFSIZE=1500
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_RXDMA=y
|
||||
CONFIG_USART3_TXBUFSIZE=3000
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_RXDMA=y
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USART6_TXDMA=y
|
||||
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"
|
|
@ -0,0 +1,194 @@
|
|||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F765IIT6 has 2048 KiB of main FLASH memory. This FLASH memory
|
||||
* can be accessed from either the AXIM interface at address 0x0800:0000 or
|
||||
* from the ITCM interface at address 0x0020:0000.
|
||||
*
|
||||
* Additional information, including the option bytes, is available at at
|
||||
* FLASH at address 0x1ff0:0000 (AXIM) or 0x0010:0000 (ITCM).
|
||||
*
|
||||
* In the STM32F765IIT6, 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 on ITCM at 0x0020:0000
|
||||
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
|
||||
* ST programmed value: System bootloader at 0x0010:0000
|
||||
*
|
||||
* NuttX does not modify these option byes. On the unmodified NUCLEO-144
|
||||
* board, the BOOT0 pin is at ground so by default, the STM32F765IIT6 will
|
||||
* boot from address 0x0020:0000 in ITCM FLASH.
|
||||
*
|
||||
* The STM32F765IIT6 also has 512 KiB of data SRAM (in addition to ITCM SRAM).
|
||||
* SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 128 KiB of DTCM SRM beginning at address 0x2000:0000
|
||||
* 2) 368 KiB of SRAM1 beginning at address 0x2002:0000
|
||||
* 3) 16 KiB of SRAM2 beginning at address 0x2007:c000
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* Bootloader reserves the first 32K bank (2 Mbytes Flash memory single bank)
|
||||
* organization (256 bits read width)
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
FLASH_ITCM (rx) : ORIGIN = 0x00208000, LENGTH = 2016K
|
||||
FLASH_AXIM (rx) : ORIGIN = 0x08008000, LENGTH = 2016K
|
||||
|
||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K
|
||||
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K
|
||||
SRAM2 (rwx) : ORIGIN = 0x2007c000, LENGTH = 16K
|
||||
}
|
||||
|
||||
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_AXIM
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > FLASH_AXIM
|
||||
|
||||
/*
|
||||
* Construction data for parameters.
|
||||
*/
|
||||
__param ALIGN(4): {
|
||||
__param_start = ABSOLUTE(.);
|
||||
KEEP(*(__param*))
|
||||
__param_end = ABSOLUTE(.);
|
||||
} > FLASH_AXIM
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > FLASH_AXIM
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > FLASH_AXIM
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
} > SRAM1 AT > FLASH_AXIM
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > SRAM1
|
||||
|
||||
/* 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_AXIM
|
||||
|
||||
_framfuncs = LOADADDR(.ramfunc);
|
||||
}
|
|
@ -0,0 +1,54 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_library(drivers_board
|
||||
can.c
|
||||
i2c.cpp
|
||||
init.c
|
||||
led.c
|
||||
sdio.c
|
||||
spi.cpp
|
||||
timer_config.cpp
|
||||
usb.c
|
||||
)
|
||||
add_dependencies(drivers_board arch_board_hw_info)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
arch_board_hw_info
|
||||
arch_spi
|
||||
drivers__led # drv_led_start
|
||||
nuttx_arch # sdio
|
||||
nuttx_drivers # sdio
|
||||
px4_layer
|
||||
)
|
|
@ -0,0 +1,272 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
*
|
||||
* HEX Cube Orange internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
#define BOARD_HAS_STATIC_MANIFEST 1
|
||||
|
||||
/* PX4IO connection configuration */
|
||||
|
||||
#define BOARD_USES_PX4IO_VERSION 2
|
||||
#define PX4IO_SERIAL_DEVICE "/dev/ttyS4"
|
||||
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
|
||||
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
|
||||
#define PX4IO_SERIAL_BASE STM32_USART6_BASE
|
||||
#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
|
||||
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX
|
||||
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX
|
||||
#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR
|
||||
#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN
|
||||
#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
|
||||
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
|
||||
|
||||
/* Configuration ************************************************************************************/
|
||||
|
||||
/* Cube Yellow GPIOs ***********************************************************************************/
|
||||
|
||||
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
|
||||
|
||||
#define GPIO_nLED_AMBER /* PE12*/ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN12)
|
||||
|
||||
/*
|
||||
* ADC channels
|
||||
*
|
||||
* These are the channel numbers of the ADCs of the microcontroller that
|
||||
* can be used by the Px4 Firmware in the adc driver
|
||||
*/
|
||||
|
||||
/* ADC defines to be used in sensors.cpp to read from a particular channel */
|
||||
|
||||
#define ADC1_CH(n) (n)
|
||||
#define ADC1_GPIO(n) GPIO_ADC1_IN##n
|
||||
|
||||
#define ADC_HW_REV_SENSE_CHANNEL 1
|
||||
|
||||
/* ADC channels */
|
||||
#define PX4_ADC_GPIO \
|
||||
/* PA2 */ ADC1_GPIO(2), \
|
||||
/* PA3 */ ADC1_GPIO(3), \
|
||||
/* PA4 */ ADC1_GPIO(4), \
|
||||
/* PC3 */ ADC1_GPIO(13), \
|
||||
/* PC4 */ ADC1_GPIO(14), \
|
||||
/* PC5 */ ADC1_GPIO(15)
|
||||
|
||||
/* Define Channel numbers must match above GPIO pins */
|
||||
#define ADC_BATTERY1_VOLTAGE_CHANNEL 2 /* PA2: BATT_VOLTAGE_SENS */
|
||||
#define ADC_BATTERY1_CURRENT_CHANNEL 3 /* PA3: BATT_CURRENT_SENS */
|
||||
#define ADC_SCALED_V5_CHANNEL 4 /* PA4: VDD_5V_SENS */
|
||||
#define ADC_BATTERY2_VOLTAGE_CHANNEL 13 /* PC3: FMU_AUX_POWER_ADC1 */
|
||||
#define ADC_BATTERY2_CURRENT_CHANNEL 14 /* PC4: FMU_AUX_ADC2 */
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15 /* PC5: PRESSURE_SENS */
|
||||
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_AIRSPEED_VOLTAGE_CHANNEL))
|
||||
|
||||
/* Define Battery 1 Voltage Divider and A per V
|
||||
*/
|
||||
|
||||
#define BOARD_BATTERY1_V_DIV (10.1f)
|
||||
#define BOARD_BATTERY1_A_PER_V (17.0f)
|
||||
|
||||
/* Define Battery 2 Voltage Divider and A per V
|
||||
*/
|
||||
|
||||
#define BOARD_BATTERY2_V_DIV (10.1f)
|
||||
#define BOARD_BATTERY2_A_PER_V (17.0f)
|
||||
|
||||
|
||||
/* PWM
|
||||
*/
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 6
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 6
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
#define BOARD_NUMBER_BRICKS 2
|
||||
#define GPIO_nVDD_BRICK1_VALID /* PB5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_nVDD_BRICK2_VALID /* PB7 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN7)
|
||||
#define GPIO_nVDD_USB_VALID /* PC0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0)
|
||||
#define GPIO_nVDD_3V3_SENSORS_EN /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_nVDD_5V_PERIPH_EN /* PA8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8)
|
||||
#define GPIO_nVDD_5V_PERIPH_OC /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15)
|
||||
#define GPIO_nVDD_5V_HIPOWER_OC /* PE10 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN10)
|
||||
|
||||
/* Define True logic Power Control in arch agnostic form */
|
||||
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, !(on_true))
|
||||
#define VDD_3V3_SENORS_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_3V3_SENSORS_EN, (on_true))
|
||||
#define VDD_5V_RC_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_RC_EN, (on_true))
|
||||
|
||||
/* Tone alarm output */
|
||||
|
||||
#define TONE_ALARM_TIMER 2 /* timer 2 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* PA15 TIM2_CH1 */
|
||||
|
||||
#define GPIO_BUZZER_1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
|
||||
|
||||
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
|
||||
#define GPIO_TONE_ALARM GPIO_TIM2_CH1OUT_2
|
||||
|
||||
/* USB OTG FS
|
||||
*
|
||||
* PA9 OTG_FS_VBUS VBUS sensing
|
||||
*/
|
||||
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
|
||||
|
||||
/* Power switch controls ******************************************************/
|
||||
|
||||
#define SDIO_SLOTNO 0 /* Only one slot */
|
||||
#define SDIO_MINOR 0
|
||||
|
||||
/* SD card bringup does not work if performed on the IDLE thread because it
|
||||
* will cause waiting. Use either:
|
||||
*
|
||||
* CONFIG_LIB_BOARDCTL=y, OR
|
||||
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \
|
||||
!defined(CONFIG_BOARD_INITTHREAD)
|
||||
# warning SDIO initialization cannot be perfomed on the IDLE thread
|
||||
#endif
|
||||
|
||||
/* 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_nVDD_5V_HIPOWER_OC))
|
||||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
|
||||
/* This board provides a DMA pool and APIs */
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||
|
||||
/* This board provides the board_on_reset interface */
|
||||
#define BOARD_HAS_ON_RESET 1
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
PX4_ADC_GPIO, \
|
||||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN2_TX, \
|
||||
GPIO_CAN2_RX, \
|
||||
GPIO_nVDD_5V_PERIPH_EN, \
|
||||
GPIO_nVDD_5V_PERIPH_OC, \
|
||||
GPIO_nVDD_5V_HIPOWER_OC, \
|
||||
GPIO_nVDD_3V3_SENSORS_EN, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
}
|
||||
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
#define BOARD_NUM_IO_TIMERS 5
|
||||
|
||||
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5};
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public data
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_sdio_initialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize SDIO-based MMC/SD card support
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int stm32_sdio_initialize(void);
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
|
||||
extern void stm32_usbinitialize(void);
|
||||
|
||||
extern void board_peripheral_reset(int ms);
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
|
@ -0,0 +1,134 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file can.c
|
||||
*
|
||||
* Board-specific CAN functions.
|
||||
*/
|
||||
|
||||
#if !defined(CONFIG_CAN)
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#else
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/can/can.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32_can.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#ifdef CONFIG_CAN
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
|
||||
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
|
||||
# undef CONFIG_STM32_CAN2
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_CAN1
|
||||
# define CAN_PORT 1
|
||||
#else
|
||||
# define CAN_PORT 2
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
int can_devinit(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following interface to work with
|
||||
* examples/can.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int can_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct can_dev_s *can;
|
||||
int ret;
|
||||
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized) {
|
||||
/* Call stm32_caninitialize() to get an instance of the CAN interface */
|
||||
|
||||
can = stm32_caninitialize(CAN_PORT);
|
||||
|
||||
if (can == NULL) {
|
||||
canerr("ERROR: Failed to get CAN interface\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the CAN driver at "/dev/can0" */
|
||||
|
||||
ret = can_register("/dev/can0", can);
|
||||
|
||||
if (ret < 0) {
|
||||
canerr("ERROR: can_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_CAN */
|
|
@ -0,0 +1,39 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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(2),
|
||||
initI2CBusExternal(1),
|
||||
};
|
|
@ -0,0 +1,261 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2019 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
|
||||
*
|
||||
* PX4FMU-specific early startup code. This file implements the
|
||||
* board_app_initializ() function that is called early by nsh during startup.
|
||||
*
|
||||
* Code here is run before the rcS script is invoked; it should start required
|
||||
* subsystems and perform board-specific initialisation.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <nuttx/mm/gran.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_uart.h>
|
||||
#include <arch/board/board.h>
|
||||
#include "up_internal.h"
|
||||
|
||||
#include <px4_arch/io_timer.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
#include <px4_platform_common/init.h>
|
||||
#include <px4_platform/gpio.h>
|
||||
#include <px4_platform/board_determine_hw_info.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
#define _GPIO_PULL_DOWN_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz))
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
__END_DECLS
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_peripheral_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_peripheral_reset(int ms)
|
||||
{
|
||||
/* set the peripheral rails off */
|
||||
|
||||
VDD_5V_PERIPH_EN(false);
|
||||
VDD_3V3_SENORS_POWER_EN(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 */
|
||||
VDD_5V_PERIPH_EN(true);
|
||||
VDD_3V3_SENORS_POWER_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)
|
||||
{
|
||||
board_on_reset(-1); /* Reset PWM first thing */
|
||||
|
||||
/* configure LEDs */
|
||||
|
||||
board_autoled_initialize();
|
||||
|
||||
/* configure pins */
|
||||
|
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||
px4_gpio_init(gpio, arraySize(gpio));
|
||||
board_control_spi_sensors_power_configgpio();
|
||||
|
||||
/* configure USB interfaces */
|
||||
|
||||
stm32_usbinitialize();
|
||||
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_app_initialize
|
||||
*
|
||||
* Description:
|
||||
* Perform application specific initialization. This function is never
|
||||
* called directly from application code, but only indirectly via the
|
||||
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
|
||||
*
|
||||
* Input Parameters:
|
||||
* arg - The boardctl() argument is passed to the board_app_initialize()
|
||||
* implementation without modification. The argument has no
|
||||
* meaning to NuttX; the meaning of the argument is a contract
|
||||
* between the board-specific initalization logic and the the
|
||||
* matching application logic. The value cold be such things as a
|
||||
* mode enumeration value, a set of DIP switch switch settings, a
|
||||
* pointer to configuration data read from a file or serial FLASH,
|
||||
* or whatever you would like to do with it. Every implementation
|
||||
* should accept zero/NULL as a default configuration.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||
* any failure to indicate the nature of the failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
/* Power on Interfaces */
|
||||
VDD_5V_PERIPH_EN(true);
|
||||
VDD_3V3_SENORS_POWER_EN(true);
|
||||
|
||||
/* Need hrt running before using the ADC */
|
||||
|
||||
px4_platform_init();
|
||||
|
||||
/* configure SPI interfaces (after we determined the HW version) */
|
||||
|
||||
stm32_spiinitialize();
|
||||
|
||||
px4_arch_configgpio(_GPIO_PULL_DOWN_INPUT(GPIO_CAN2_RX));
|
||||
|
||||
/* configure the DMA allocator */
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
#if defined(SERIAL_HAVE_RXDMA)
|
||||
/* set up the serial DMA polling */
|
||||
static struct hrt_call serial_dma_call;
|
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered
|
||||
* a DMA event.
|
||||
*/
|
||||
struct timespec ts;
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = 1000000;
|
||||
|
||||
hrt_call_every(&serial_dma_call,
|
||||
ts_to_abstime(&ts),
|
||||
ts_to_abstime(&ts),
|
||||
(hrt_callout)stm32_serial_dma_poll,
|
||||
NULL);
|
||||
#endif
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_AMBER);
|
||||
|
||||
if (board_hardfault_init(2, true) != 0) {
|
||||
led_on(LED_AMBER);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
int ret = stm32_sdio_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_AMBER);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -0,0 +1,99 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 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
|
||||
*
|
||||
* PX4FMU LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
#define xlat(p) (p)
|
||||
|
||||
__EXPORT void led_init(void)
|
||||
{
|
||||
/* Configure LED GPIOs for output */
|
||||
stm32_configgpio(GPIO_nLED_AMBER);
|
||||
}
|
||||
|
||||
static void phy_set_led(int led, bool state)
|
||||
{
|
||||
/* Drive Low to switch on */
|
||||
|
||||
stm32_gpiowrite(GPIO_nLED_AMBER, !state);
|
||||
}
|
||||
|
||||
static bool phy_get_led(int led)
|
||||
{
|
||||
/* If Low it is on */
|
||||
return !stm32_gpioread(GPIO_nLED_AMBER);
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
phy_set_led(xlat(led), true);
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
phy_set_led(xlat(led), false);
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
phy_set_led(xlat(led), !phy_get_led(xlat(led)));
|
||||
}
|
|
@ -0,0 +1,177 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "board_config.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "stm32_sdmmc.h"
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Card detections requires card support and a card detection GPIO */
|
||||
|
||||
#define HAVE_NCD 1
|
||||
#if !defined(GPIO_SDMMC1_NCD)
|
||||
# undef HAVE_NCD
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static FAR struct sdio_dev_s *sdio_dev;
|
||||
#ifdef HAVE_NCD
|
||||
static bool g_sd_inserted = 0xff; /* Impossible value */
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_ncd_interrupt
|
||||
*
|
||||
* Description:
|
||||
* Card detect interrupt handler.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef HAVE_NCD
|
||||
static int stm32_ncd_interrupt(int irq, FAR void *context)
|
||||
{
|
||||
bool present;
|
||||
|
||||
present = !stm32_gpioread(GPIO_SDMMC1_NCD);
|
||||
|
||||
if (sdio_dev && present != g_sd_inserted) {
|
||||
sdio_mediachange(sdio_dev, present);
|
||||
g_sd_inserted = present;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_sdio_initialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize SDIO-based MMC/SD card support
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int stm32_sdio_initialize(void)
|
||||
{
|
||||
int ret;
|
||||
|
||||
#ifdef HAVE_NCD
|
||||
/* Card detect */
|
||||
|
||||
bool cd_status;
|
||||
|
||||
/* Configure the card detect GPIO */
|
||||
|
||||
stm32_configgpio(GPIO_SDMMC1_NCD);
|
||||
|
||||
/* Register an interrupt handler for the card detect pin */
|
||||
|
||||
stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt);
|
||||
#endif
|
||||
|
||||
/* Mount the SDIO-based MMC/SD block driver */
|
||||
/* First, get an instance of the SDIO interface */
|
||||
|
||||
finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO);
|
||||
|
||||
sdio_dev = sdio_initialize(SDIO_SLOTNO);
|
||||
|
||||
if (!sdio_dev) {
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Now bind the SDIO interface to the MMC/SD driver */
|
||||
|
||||
finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR);
|
||||
|
||||
ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev);
|
||||
|
||||
if (ret != OK) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
finfo("Successfully bound SDIO to the MMC/SD driver\n");
|
||||
|
||||
#ifdef HAVE_NCD
|
||||
/* Use SD card detect pin to check if a card is g_sd_inserted */
|
||||
|
||||
cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD);
|
||||
finfo("Card detect : %d\n", cd_status);
|
||||
|
||||
sdio_mediachange(sdio_dev, cd_status);
|
||||
#else
|
||||
/* Assume that the SD card is inserted. What choice do we have? */
|
||||
|
||||
sdio_mediachange(sdio_dev, true);
|
||||
#endif
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
|
@ -0,0 +1,53 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/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_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortD, GPIO::Pin7}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortC, GPIO::Pin2}),
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin10})
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI4, {
|
||||
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortC, GPIO::Pin14}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortC, GPIO::Pin13}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20948, SPI::CS{GPIO::PortE, GPIO::Pin4}),
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
|
@ -0,0 +1,130 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer1, DMA{DMA::Index2, DMA::Stream5, DMA::Channel6}),
|
||||
initIOTimer(Timer::Timer4),
|
||||
initIOTimer(Timer::Timer12),
|
||||
initIOTimer(Timer::Timer2),
|
||||
initIOTimer(Timer::Timer9),
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||
|
||||
#if defined(BOARD_HAS_LED_PWM) || defined(BOARD_HAS_UI_LED_PWM)
|
||||
constexpr io_timers_t led_pwm_timers[MAX_LED_TIMERS] = {
|
||||
# if defined(BOARD_HAS_UI_LED_PWM)
|
||||
initIOTimer(Timer::Timer5),
|
||||
# endif
|
||||
# if defined(BOARD_HAS_LED_PWM) && !defined(BOARD_HAS_CONTROL_STATUS_LEDS)
|
||||
initIOTimer(Timer::Timer3),
|
||||
# endif
|
||||
};
|
||||
|
||||
/* Support driving active low (preferred) or active high LED
|
||||
* on both the onboard status LEDs or the [n]UI_LED_<color>[_EXTERNAL]
|
||||
*
|
||||
* Use open drain to drive the LED. This will ensure that
|
||||
* if the LED has a 5 Volt supply that the LED will be
|
||||
* off when high.
|
||||
*/
|
||||
#define CCER_C1_NUM_BITS 4
|
||||
#define ACTIVE_LOW(c) (GTIM_CCER_CC1P << (((c)-1) * CCER_C1_NUM_BITS))
|
||||
#define ACTIVE_HIGH(c) 0
|
||||
|
||||
#if defined(BOARD_LED_PWM_DRIVE_ACTIVE_LOW)
|
||||
# define POLARITY(c) ACTIVE_LOW(c)
|
||||
# define DRIVE_TYPE(p) ((p)|GPIO_OPENDRAIN)
|
||||
#else
|
||||
# define POLARITY(c) ACTIVE_HIGH((c))
|
||||
# define DRIVE_TYPE(p) (p)
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_UI_LED_PWM_DRIVE_ACTIVE_LOW)
|
||||
# define UI_POLARITY(c) ACTIVE_LOW(c)
|
||||
# define UI_DRIVE_TYPE(p) ((p)|GPIO_OPENDRAIN)
|
||||
#else
|
||||
# define UI_POLARITY(c) ACTIVE_HIGH((c))
|
||||
# define UI_DRIVE_TYPE(p) (p)
|
||||
#endif
|
||||
|
||||
static inline constexpr timer_io_channels_t initIOTimerChannelUILED(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 = UI_DRIVE_TYPE(ret.gpio_out);
|
||||
ret.masks = UI_POLARITY(ui_polarity);
|
||||
return ret;
|
||||
}
|
||||
|
||||
static inline constexpr timer_io_channels_t initIOTimerChannelControlLED(const io_timers_t
|
||||
io_timers_conf[MAX_LED_TIMERS],
|
||||
Timer::TimerChannel timer, GPIO::GPIOPin pin, int polarity)
|
||||
{
|
||||
timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, timer, pin);
|
||||
ret.gpio_out = DRIVE_TYPE(ret.gpio_out);
|
||||
ret.masks = POLARITY(polarity);
|
||||
return ret;
|
||||
}
|
||||
|
||||
constexpr timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = {
|
||||
# if defined(BOARD_HAS_UI_LED_PWM)
|
||||
# if defined(BOARD_UI_LED_SWAP_RG)
|
||||
initIOTimerChannelUILED(led_pwm_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}, 2),
|
||||
initIOTimerChannelUILED(led_pwm_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}, 1),
|
||||
initIOTimerChannelUILED(led_pwm_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}, 3),
|
||||
# else
|
||||
initIOTimerChannelUILED(led_pwm_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}, 1),
|
||||
initIOTimerChannelUILED(led_pwm_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}, 2),
|
||||
initIOTimerChannelUILED(led_pwm_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}, 3),
|
||||
# endif
|
||||
# endif
|
||||
# if defined(BOARD_HAS_LED_PWM) && !defined(BOARD_HAS_CONTROL_STATUS_LEDS)
|
||||
initIOTimerChannelControlLED(led_pwm_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}, 4),
|
||||
initIOTimerChannelControlLED(led_pwm_timers, {Timer::Timer3, Timer::Channel1}, {GPIO::PortC, GPIO::Pin6}, 1),
|
||||
initIOTimerChannelControlLED(led_pwm_timers, {Timer::Timer3, Timer::Channel2}, {GPIO::PortC, GPIO::Pin7}, 2),
|
||||
# endif
|
||||
};
|
||||
#endif // BOARD_HAS_LED_PWM || BOARD_HAS_UI_LED_PWM
|
|
@ -0,0 +1,105 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file usb.c
|
||||
*
|
||||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
|
||||
#include <up_arch.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include <stm32_otg.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to setup USB-related GPIO pins for the PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbinitialize(void)
|
||||
{
|
||||
/* The OTG FS has an internal soft pull-up */
|
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
|
||||
|
||||
#ifdef CONFIG_STM32F7_OTGFS
|
||||
stm32_configgpio(GPIO_OTGFS_VBUS);
|
||||
#endif
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend
|
||||
*
|
||||
* Description:
|
||||
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
|
||||
* used. This function is called whenever the USB enters or leaves suspend mode.
|
||||
* This is an opportunity for the board logic to shutdown clocks, power, etc.
|
||||
* while the USB is suspended.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
uinfo("resume: %d\n", resume);
|
||||
}
|
Loading…
Reference in New Issue