Browse Source
Durandal:Fix PLL settings durandal-v1:Move I2C123, I2C4 to HSI. Not liking using HSI but, F7 has, and in reality there is no requerment for accuracy. durandal-v1:board config set 400kHz on card probe durandal-v1:Board SDMMC Clock Not greater then 25 mHz durandal-v1:Fix PLL3 configuration typo and value CI build config for holybro_durandal-v1 durandal-v1:Kconfig - add knob to ensure ARCH_MATH_H is kept Upstream changes added ARCH_HAVE_MATH_H to protect from archs without math.h from causing isses for users setting CONFIG_ARCH_MATH_H and getting errors. PX4 provides a math.h and we need CONFIG_ARCH_MATH_H set. So this Selects ARCH_HAVE_MATH_H perserving CONFIG_ARCH_MATH_H a defconfig Track master LED removal durandal-v1: bmi055 -> bmi088 bmi088 is what the board uses durandal-v1:add PX4IO support durandal-v1 rc.board_sensors: start baro durandal-v1: remove segway module durandal:Run at 480 Mhz durandal-v1: build thermal control module durandal-v1: enable IMU thermal control by default durandal-v1:Track upstream adc start moved to rc.board_sensors durandal-v1:Track upstream mavlink start moved to rc.board_mavlinksbg
22 changed files with 3406 additions and 1 deletions
@ -0,0 +1,126 @@
@@ -0,0 +1,126 @@
|
||||
|
||||
px4_add_board( |
||||
PLATFORM nuttx |
||||
VENDOR holybro |
||||
MODEL durandal-v1 |
||||
LABEL default |
||||
TOOLCHAIN arm-none-eabi |
||||
ARCHITECTURE cortex-m7 |
||||
ROMFSROOT px4fmu_common |
||||
IO px4_io-v2_default |
||||
TESTING |
||||
# UAVCAN_INTERFACES 2 - No H7 or FD can support in UAVCAN |
||||
|
||||
SERIAL_PORTS |
||||
GPS1:/dev/ttyS0 |
||||
TEL1:/dev/ttyS1 |
||||
TEL2:/dev/ttyS2 |
||||
TEL4:/dev/ttyS3 |
||||
|
||||
DRIVERS |
||||
adc |
||||
barometer # all available barometer drivers |
||||
batt_smbus |
||||
camera_capture |
||||
camera_trigger |
||||
differential_pressure # all available differential pressure drivers |
||||
distance_sensor # all available distance sensor drivers |
||||
# dshot -- todo needslooking at |
||||
gps |
||||
heater |
||||
imu/adis16448 |
||||
imu/adis16497 |
||||
#imu # all available imu drivers |
||||
imu/bmi088 |
||||
imu/mpu6000 |
||||
imu/mpu9250 |
||||
irlock |
||||
lights/blinkm |
||||
lights/rgbled |
||||
lights/rgbled_ncp5623c |
||||
magnetometer # all available magnetometer drivers |
||||
#md25 |
||||
mkblctrl |
||||
optical_flow # all available optical flow drivers |
||||
pca9685 |
||||
power_monitor/ina226 |
||||
#protocol_splitter |
||||
# pwm_input - Need to create arch/stm32 arch/stm32h7 arch/kinetis and reloacate |
||||
# all arch dependant code there |
||||
pwm_out_sim |
||||
px4fmu |
||||
px4io |
||||
roboclaw |
||||
tap_esc |
||||
telemetry # all available telemetry drivers |
||||
test_ppm |
||||
tone_alarm |
||||
# uavcan - No H7 or FD can support in UAVCAN yet |
||||
|
||||
MODULES |
||||
attitude_estimator_q |
||||
camera_feedback |
||||
commander |
||||
dataman |
||||
ekf2 |
||||
events |
||||
fw_att_control |
||||
fw_pos_control_l1 |
||||
rover_pos_control |
||||
land_detector |
||||
landing_target_estimator |
||||
load_mon |
||||
local_position_estimator |
||||
logger |
||||
mavlink |
||||
mc_att_control |
||||
mc_pos_control |
||||
navigator |
||||
battery_status |
||||
sensors |
||||
sih |
||||
vmount |
||||
vtol_att_control |
||||
airspeed_selector |
||||
|
||||
SYSTEMCMDS |
||||
bl_update |
||||
config |
||||
dmesg |
||||
dumpfile |
||||
esc_calib |
||||
hardfault_log |
||||
i2cdetect |
||||
led_control |
||||
mixer |
||||
motor_ramp |
||||
motor_test |
||||
mtd |
||||
nshterm |
||||
param |
||||
perf |
||||
pwm |
||||
reboot |
||||
reflect |
||||
sd_bench |
||||
shutdown |
||||
tests # tests and test runner |
||||
top |
||||
topic_listener |
||||
tune_control |
||||
usb_connected |
||||
ver |
||||
work_queue |
||||
|
||||
EXAMPLES |
||||
bottle_drop # OBC challenge |
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||
hello |
||||
hwtest # Hardware test |
||||
#matlab_csv_serial |
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html |
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html |
||||
rover_steering_control # Rover example app |
||||
uuv_example_app |
||||
|
||||
) |
@ -0,0 +1,13 @@
@@ -0,0 +1,13 @@
|
||||
{ |
||||
"board_id": 139, |
||||
"magic": "PX4FWv1", |
||||
"description": "Firmware for the Durandalv1 board", |
||||
"image": "", |
||||
"build_time": 0, |
||||
"summary": "DURANDALv1", |
||||
"version": "0.1", |
||||
"image_size": 0, |
||||
"image_maxsize": 1966080, |
||||
"git_identity": "", |
||||
"board_revision": 0 |
||||
} |
@ -0,0 +1,13 @@
@@ -0,0 +1,13 @@
|
||||
#!/bin/sh |
||||
# |
||||
# Holybro Durandal V1 specific board defaults |
||||
#------------------------------------------------------------------------------ |
||||
|
||||
|
||||
if [ $AUTOCNF = yes ] |
||||
then |
||||
# Enable IMU thermal control |
||||
param set SENS_EN_THERMAL 1 |
||||
fi |
||||
|
||||
set LOGGER_BUF 64 |
@ -0,0 +1,7 @@
@@ -0,0 +1,7 @@
|
||||
#!/bin/sh |
||||
# |
||||
# Durandal specific specific board MAVLink startup script. |
||||
#------------------------------------------------------------------------------ |
||||
|
||||
# Start MAVLink on the USB port |
||||
mavlink start -d /dev/ttyACM0 |
@ -0,0 +1,30 @@
@@ -0,0 +1,30 @@
|
||||
#!/bin/sh |
||||
# |
||||
# Holybro Durandal V1 specific board sensors init |
||||
#------------------------------------------------------------------------------ |
||||
adc start |
||||
|
||||
# Internal SPI bus ICM-20689 |
||||
mpu6000 -R 8 -z -T 20689 start |
||||
|
||||
# Internal SPI bus BMI088 accel |
||||
bmi088 -A -R 10 start |
||||
|
||||
# Internal SPI bus BMI088 gyro |
||||
bmi088 -G -R 10 start |
||||
|
||||
# Possible external compasses |
||||
ist8310 -C -b 1 start |
||||
ist8310 -C -b 2 start |
||||
hmc5883 -C -T -X start |
||||
qmc5883 -X start |
||||
lis3mdl -X start |
||||
|
||||
# Possible internal compass |
||||
ist8310 -C -b 5 start |
||||
|
||||
# Possible pmw3901 optical flow sensor |
||||
pmw3901 start |
||||
|
||||
# Baro on internal SPI |
||||
ms5611 -s start |
@ -0,0 +1,23 @@
@@ -0,0 +1,23 @@
|
||||
# |
||||
# For a description of the syntax of this configuration file, |
||||
# see misc/tools/kconfig-language.txt. |
||||
# |
||||
config BOARD_HAS_PROBES |
||||
bool "Board provides GPIO or other Hardware for signaling to timing analyze." |
||||
default y |
||||
---help--- |
||||
This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. |
||||
|
||||
config BOARD_USE_PROBES |
||||
bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" |
||||
default n |
||||
depends on BOARD_HAS_PROBES |
||||
|
||||
---help--- |
||||
Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. |
||||
|
||||
# Hack to ensure ARCH_MATH_H is kept |
||||
config BOARD_HAVE_MATH_H |
||||
bool "Provide ARCH math.h (selects ARCH_HAVE_MATH_H)" |
||||
default y |
||||
select ARCH_HAVE_MATH_H |
@ -0,0 +1 @@
@@ -0,0 +1 @@
|
||||
|
@ -0,0 +1,551 @@
@@ -0,0 +1,551 @@
|
||||
/************************************************************************************
|
||||
* nuttx-configs/holybro/durandal-v1/include/board.h |
||||
* |
||||
* Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. |
||||
* Authors: David Sidrane <david.sidrane@nscdg.com> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name NuttX nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
************************************************************************************/ |
||||
#ifndef __NUTTX_CONFIG_HOLYBRO_DURANDAL_V1_INCLUDE_BOARD_H |
||||
#define __NUTTX_CONFIG_HOLYBRO_DURANDAL_V1_INCLUDE_BOARD_H |
||||
|
||||
/************************************************************************************
|
||||
* Included Files |
||||
************************************************************************************/ |
||||
|
||||
#include <nuttx/config.h> |
||||
|
||||
#ifndef __ASSEMBLY__ |
||||
# include <stdint.h> |
||||
#endif |
||||
|
||||
#include "stm32_rcc.h" |
||||
#include "stm32_sdmmc.h" |
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions |
||||
************************************************************************************/ |
||||
|
||||
/* Clocking *************************************************************************/ |
||||
/* The holybro durandal v1 board provides the following clock sources:
|
||||
* |
||||
* X1: 16 MHz crystal for HSE |
||||
* |
||||
* So we have these clock source available within the STM32 |
||||
* |
||||
* HSI: 16 MHz RC factory-trimmed |
||||
* HSE: 16 MHz crystal for HSE |
||||
*/ |
||||
|
||||
#define STM32_BOARD_XTAL 16000000ul |
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul |
||||
#define STM32_LSI_FREQUENCY 32000 |
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL |
||||
#define STM32_LSE_FREQUENCY 32768 |
||||
|
||||
/* Main PLL Configuration.
|
||||
* |
||||
* PLL source is HSE = 16,000,000 |
||||
* |
||||
* PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN |
||||
* Subject to: |
||||
* |
||||
* 1 <= PLLM <= 63 |
||||
* 4 <= PLLN <= 512 |
||||
* 150 MHz <= PLL_VCOL <= 420MHz |
||||
* 192 MHz <= PLL_VCOH <= 836MHz |
||||
* |
||||
* SYSCLK = PLL_VCO / PLLP |
||||
* CPUCLK = SYSCLK / D1CPRE |
||||
* Subject to |
||||
* |
||||
* PLLP1 = {2, 4, 6, 8, ..., 128} |
||||
* PLLP2,3 = {2, 3, 4, ..., 128} |
||||
* CPUCLK <= 480 MHz |
||||
*/ |
||||
|
||||
#define STM32_BOARD_USEHSE |
||||
|
||||
#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE |
||||
|
||||
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
|
||||
* |
||||
* PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz |
||||
* |
||||
* PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz |
||||
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz |
||||
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz |
||||
*/ |
||||
|
||||
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ |
||||
RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \
|
||||
RCC_PLLCFGR_DIVP1EN | \
|
||||
RCC_PLLCFGR_DIVQ1EN | \
|
||||
RCC_PLLCFGR_DIVR1EN) |
||||
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) |
||||
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) |
||||
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) |
||||
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) |
||||
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) |
||||
|
||||
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) |
||||
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) |
||||
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) |
||||
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) |
||||
|
||||
/* PLL2 */ |
||||
|
||||
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ |
||||
RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \
|
||||
RCC_PLLCFGR_DIVP2EN | \
|
||||
RCC_PLLCFGR_DIVQ2EN | \
|
||||
RCC_PLLCFGR_DIVR2EN) |
||||
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) |
||||
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) |
||||
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) |
||||
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) |
||||
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) |
||||
|
||||
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) |
||||
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) |
||||
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) |
||||
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) |
||||
|
||||
/* PLL3 */ |
||||
|
||||
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ |
||||
RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \
|
||||
RCC_PLLCFGR_DIVQ3EN) |
||||
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) |
||||
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) |
||||
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) |
||||
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) |
||||
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) |
||||
|
||||
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) |
||||
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) |
||||
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) |
||||
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) |
||||
|
||||
/* SYSCLK = PLL1P = 480MHz
|
||||
* CPUCLK = SYSCLK / 1 = 480 MHz |
||||
*/ |
||||
|
||||
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) |
||||
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) |
||||
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) |
||||
|
||||
/* Configure Clock Assignments */ |
||||
|
||||
/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max)
|
||||
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 |
||||
*/ |
||||
|
||||
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ |
||||
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ |
||||
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ |
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ |
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ |
||||
|
||||
#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ |
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) |
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ |
||||
|
||||
#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ |
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) |
||||
|
||||
/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ |
||||
|
||||
#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ |
||||
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) |
||||
|
||||
/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ |
||||
|
||||
#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ |
||||
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) |
||||
|
||||
/* Timer clock frequencies */ |
||||
|
||||
/* Timers driven from APB1 will be twice PCLK1 */ |
||||
|
||||
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
|
||||
/* Timers driven from APB2 will be twice PCLK2 */ |
||||
|
||||
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) |
||||
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) |
||||
#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) |
||||
#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) |
||||
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) |
||||
|
||||
/* Kernel Clock Configuration
|
||||
* |
||||
* Note: look at Table 54 in ST Manual |
||||
*/ |
||||
|
||||
/* I2C123 clock source */ |
||||
|
||||
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI |
||||
|
||||
/* I2C4 clock source */ |
||||
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI |
||||
|
||||
/* SPI123 clock source */ |
||||
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 |
||||
|
||||
/* SPI45 clock source */ |
||||
|
||||
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 |
||||
|
||||
/* SPI6 clock source */ |
||||
|
||||
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 |
||||
|
||||
/* USB 1 and 2 clock source */ |
||||
|
||||
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 |
||||
|
||||
/* ADC 1 2 3 clock source */ |
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 |
||||
|
||||
/* FLASH wait states
|
||||
* |
||||
* ------------ ---------- ----------- |
||||
* Vcore MAX ACLK WAIT STATES |
||||
* ------------ ---------- ----------- |
||||
* 1.15-1.26 V 70 MHz 0 |
||||
* (VOS1 level) 140 MHz 1 |
||||
* 210 MHz 2 |
||||
* 1.05-1.15 V 55 MHz 0 |
||||
* (VOS2 level) 110 MHz 1 |
||||
* 165 MHz 2 |
||||
* 220 MHz 3 |
||||
* 0.95-1.05 V 45 MHz 0 |
||||
* (VOS3 level) 90 MHz 1 |
||||
* 135 MHz 2 |
||||
* 180 MHz 3 |
||||
* 225 MHz 4 |
||||
* ------------ ---------- ----------- |
||||
*/ |
||||
|
||||
#define BOARD_FLASH_WAITSTATES 2 |
||||
|
||||
/* SDMMC definitions ********************************************************/ |
||||
|
||||
/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ |
||||
|
||||
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) |
||||
|
||||
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
|
||||
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s |
||||
*/ |
||||
|
||||
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) |
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) |
||||
#else |
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) |
||||
#endif |
||||
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) |
||||
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) |
||||
#else |
||||
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) |
||||
#endif |
||||
|
||||
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE |
||||
|
||||
/* LED definitions ******************************************************************/ |
||||
/* The holybro durandal v1 board has three, LED_GREEN a Green LED, LED_BLUE
|
||||
* a Blue LED and LED_RED a Red LED, that can be controlled by software. |
||||
* |
||||
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. |
||||
* The following definitions are used to access individual LEDs. |
||||
*/ |
||||
|
||||
/* LED index values for use with board_userled() */ |
||||
|
||||
#define BOARD_LED1 0 |
||||
#define BOARD_LED2 1 |
||||
#define BOARD_LED3 2 |
||||
#define BOARD_NLEDS 3 |
||||
|
||||
#define BOARD_LED_RED BOARD_LED1 |
||||
#define BOARD_LED_GREEN BOARD_LED2 |
||||
#define BOARD_LED_BLUE BOARD_LED3 |
||||
|
||||
/* LED bits for use with board_userled_all() */ |
||||
|
||||
#define BOARD_LED1_BIT (1 << BOARD_LED1) |
||||
#define BOARD_LED2_BIT (1 << BOARD_LED2) |
||||
#define BOARD_LED3_BIT (1 << BOARD_LED3) |
||||
|
||||
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
|
||||
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related |
||||
* events as follows: |
||||
* |
||||
* |
||||
* SYMBOL Meaning LED state |
||||
* Red Green Blue |
||||
* ---------------------- -------------------------- ------ ------ ----*/ |
||||
|
||||
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ |
||||
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ |
||||
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ |
||||
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ |
||||
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ |
||||
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ |
||||
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ |
||||
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ |
||||
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ |
||||
|
||||
/* Thus if the Green LED is statically on, NuttX has successfully booted and
|
||||
* is, apparently, running normally. If the Red LED is flashing at |
||||
* approximately 2Hz, then a fatal error has been detected and the system |
||||
* has halted. |
||||
*/ |
||||
|
||||
/* Alternate function pin selections ************************************************/ |
||||
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */ |
||||
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ |
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ |
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ |
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ |
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */ |
||||
|
||||
#define GPIO_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_NSS_2 /* PD11 */ |
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */ |
||||
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */ |
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_2 /* PG9 */ |
||||
#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */ |
||||
#define GPIO_USART6_RTS GPIO_USART6_RTS_2 /* PG8 */ |
||||
#define GPIO_USART6_CTS GPIO_USART6_CTS_NSS_2 /* PG15 */ |
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ |
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ |
||||
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ |
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ |
||||
|
||||
/* UART RX DMA configurations */ |
||||
|
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2 |
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 |
||||
#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_0 /* DMA1:81 */ |
||||
#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_0 /* DMA1:82 */ |
||||
|
||||
/* CAN
|
||||
* |
||||
* CAN1 is routed to transceiver. |
||||
* CAN2 is routed to transceiver. |
||||
*/ |
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PI9 */ |
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_4 /* PH13 */ |
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ |
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */ |
||||
|
||||
/* SPI
|
||||
* SPI1 sensors |
||||
* SPI2 is FRAM. |
||||
* SPI4 is BARO |
||||
* SPI6 Reserved |
||||
*/ |
||||
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ |
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */ |
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_3 /* PG11 */ |
||||
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ |
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ |
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_6 /* PI1 */ |
||||
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */ |
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */ |
||||
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_2 /* PE2 */ |
||||
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */ |
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */ |
||||
#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1 /* PF7 */ |
||||
|
||||
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */ |
||||
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_3 /* PB5 */ |
||||
#define GPIO_SPI6_SCK GPIO_SPI6_SCK_1 /* PG13 */ |
||||
|
||||
/* I2C
|
||||
* |
||||
* Each I2C is associated with a U[S]ART |
||||
* hence the naming I2C2_SDA_UART4 in FMU USAGE spreadsheet |
||||
* |
||||
* The optional _GPIO configurations allow the I2C driver to manually |
||||
* reset the bus to clear stuck slaves. They match the pin configuration, |
||||
* but are normally-high GPIOs. |
||||
* |
||||
*/ |
||||
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ |
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ |
||||
|
||||
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) |
||||
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) |
||||
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */ |
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */ |
||||
|
||||
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1) |
||||
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0) |
||||
|
||||
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */ |
||||
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ |
||||
|
||||
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN7) |
||||
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8) |
||||
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ |
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ |
||||
|
||||
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14) |
||||
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15) |
||||
|
||||
/* SDMMC1
|
||||
* |
||||
* VDD 3.3 |
||||
* GND |
||||
* SDMMC1_CK PC12 |
||||
* SDMMC1_CMD PD2 |
||||
* SDMMC1_D0 PC8 |
||||
* SDMMC1_D1 PC9 |
||||
* SDMMC1_D2 PC10 |
||||
* SDMMC1_D3 PC11 |
||||
* GPIO_SDMMC1_NCD PG0 |
||||
*/ |
||||
|
||||
/* USB
|
||||
* |
||||
* OTG_FS_DM PA11 |
||||
* OTG_FS_DP PA12 |
||||
* VBUS PA9 |
||||
*/ |
||||
|
||||
|
||||
/* Board provides GPIO or other Hardware for signaling to timing analyzer */ |
||||
|
||||
#if defined(CONFIG_BOARD_USE_PROBES) |
||||
# include "stm32_gpio.h" |
||||
# define PROBE_N(n) (1<<((n)-1)) |
||||
# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14) /* PE14 AUX1 */ |
||||
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN10) /* PA10 AUX2 */ |
||||
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 AUX3 */ |
||||
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) /* PE9 AUX4 */ |
||||
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ |
||||
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 FMU_CAP6 */ |
||||
# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 FMU_CAP5 */ |
||||
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 FMU_CAP4 */ |
||||
# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN5) /* PA5 FMU_CAP3 */ |
||||
# define PROBE_10 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN3) /* PB3 FMU_CAP2 */ |
||||
# define PROBE_11 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN11) /* PB11 FMU_CAP1 */ |
||||
|
||||
# define PROBE_INIT(mask) \ |
||||
do { \
|
||||
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
|
||||
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
|
||||
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
|
||||
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
|
||||
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
|
||||
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
|
||||
if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
|
||||
if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
|
||||
if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \
|
||||
if ((mask)& PROBE_N(10)) { stm32_configgpio(PROBE_10); } \
|
||||
if ((mask)& PROBE_N(11)) { stm32_configgpio(PROBE_11); } \
|
||||
} while(0) |
||||
|
||||
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) |
||||
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) |
||||
#else |
||||
# define PROBE_INIT(mask) |
||||
# define PROBE(n,s) |
||||
# define PROBE_MARK(n) |
||||
#endif |
||||
|
||||
/************************************************************************************
|
||||
* 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_HOLYBRO_DURANDAL_V1_INCLUDE_BOARD_H */ |
@ -0,0 +1,256 @@
@@ -0,0 +1,256 @@
|
||||
# |
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT. |
||||
# |
||||
# You can use "make menuconfig" to make any modifications to the installed .config file. |
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your |
||||
# modifications. |
||||
# |
||||
# CONFIG_DISABLE_OS_API is not set |
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set |
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set |
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set |
||||
# CONFIG_MMCSD_MMCSUPPORT is not set |
||||
# CONFIG_MMCSD_SPI is not set |
||||
# CONFIG_NSH_DISABLEBG is not set |
||||
# CONFIG_NSH_DISABLESCRIPT is not set |
||||
# CONFIG_NSH_DISABLE_DF is not set |
||||
# CONFIG_NSH_DISABLE_EXEC is not set |
||||
# CONFIG_NSH_DISABLE_EXIT is not set |
||||
# CONFIG_NSH_DISABLE_GET is not set |
||||
# CONFIG_NSH_DISABLE_ITEF is not set |
||||
# CONFIG_NSH_DISABLE_LOOPS is not set |
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set |
||||
# CONFIG_NSH_DISABLE_TIME is not set |
||||
CONFIG_ARCH="arm" |
||||
CONFIG_ARCH_BOARD_CUSTOM=y |
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config" |
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y |
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" |
||||
CONFIG_ARCH_CHIP="stm32h7" |
||||
CONFIG_ARCH_CHIP_STM32H743ZI=y |
||||
CONFIG_ARCH_CHIP_STM32H7=y |
||||
CONFIG_ARCH_INTERRUPTSTACK=512 |
||||
CONFIG_ARCH_MATH_H=y |
||||
CONFIG_ARCH_STACKDUMP=y |
||||
CONFIG_ARMV7M_BASEPRI_WAR=y |
||||
CONFIG_ARMV7M_DCACHE=y |
||||
CONFIG_ARMV7M_DTCM=y |
||||
CONFIG_ARMV7M_ICACHE=y |
||||
CONFIG_ARMV7M_MEMCPY=y |
||||
CONFIG_ARMV7M_USEBASEPRI=y |
||||
CONFIG_BOARDCTL_RESET=y |
||||
CONFIG_BOARD_CRASHDUMP=y |
||||
CONFIG_BOARD_LOOPSPERMSEC=95150 |
||||
CONFIG_BOARD_RESET_ON_ASSERT=2 |
||||
CONFIG_BUILTIN=y |
||||
CONFIG_C99_BOOL8=y |
||||
CONFIG_CDCACM=y |
||||
CONFIG_CDCACM_PRODUCTID=0x008b |
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 DurandalV1" |
||||
CONFIG_CDCACM_RXBUFSIZE=600 |
||||
CONFIG_CDCACM_TXBUFSIZE=12000 |
||||
CONFIG_CDCACM_VENDORID=0x26ac |
||||
CONFIG_CDCACM_VENDORSTR="Holybro" |
||||
CONFIG_CLOCK_MONOTONIC=y |
||||
CONFIG_DEBUG_FULLOPT=y |
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y |
||||
CONFIG_DEBUG_SYMBOLS=y |
||||
CONFIG_DEFAULT_SMALL=y |
||||
CONFIG_DEV_FIFO_SIZE=0 |
||||
CONFIG_DEV_PIPE_MAXSIZE=1024 |
||||
CONFIG_DEV_PIPE_SIZE=70 |
||||
CONFIG_EXPERIMENTAL=y |
||||
CONFIG_FAT_DMAMEMORY=y |
||||
CONFIG_FAT_LCNAMES=y |
||||
CONFIG_FAT_LFN=y |
||||
CONFIG_FAT_LFN_ALIAS_HASH=y |
||||
CONFIG_FDCLONE_STDIO=y |
||||
CONFIG_FS_BINFS=y |
||||
CONFIG_FS_CROMFS=y |
||||
CONFIG_FS_FAT=y |
||||
CONFIG_FS_FATTIME=y |
||||
CONFIG_FS_PROCFS=y |
||||
CONFIG_FS_PROCFS_EXCLUDE_BLOCKS=y |
||||
CONFIG_FS_PROCFS_EXCLUDE_MOUNT=y |
||||
CONFIG_FS_PROCFS_EXCLUDE_MOUNTS=y |
||||
CONFIG_FS_PROCFS_EXCLUDE_PARTITIONS=y |
||||
CONFIG_FS_PROCFS_EXCLUDE_USAGE=y |
||||
CONFIG_FS_PROCFS_REGISTER=y |
||||
CONFIG_FS_ROMFS=y |
||||
CONFIG_GRAN=y |
||||
CONFIG_GRAN_INTR=y |
||||
CONFIG_HAVE_CXX=y |
||||
CONFIG_HAVE_CXXINITIALIZE=y |
||||
CONFIG_I2C=y |
||||
CONFIG_I2C_RESET=y |
||||
CONFIG_IDLETHREAD_STACKSIZE=750 |
||||
CONFIG_LIBC_FLOATINGPOINT=y |
||||
CONFIG_LIBC_LONG_LONG=y |
||||
CONFIG_LIBC_STRERROR=y |
||||
CONFIG_MAX_TASKS=64 |
||||
CONFIG_MAX_WDOGPARMS=2 |
||||
CONFIG_MEMSET_64BIT=y |
||||
CONFIG_MEMSET_OPTSPEED=y |
||||
CONFIG_MMCSD=y |
||||
CONFIG_MMCSD_MULTIBLOCK_DISABLE=y |
||||
CONFIG_MMCSD_SDIO=y |
||||
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y |
||||
CONFIG_MM_REGIONS=3 |
||||
CONFIG_MTD=y |
||||
CONFIG_MTD_BYTE_WRITE=y |
||||
CONFIG_MTD_PARTITION=y |
||||
CONFIG_MTD_PROGMEM=y |
||||
CONFIG_MTD_RAMTRON=y |
||||
CONFIG_NFILE_DESCRIPTORS=20 |
||||
CONFIG_NFILE_STREAMS=8 |
||||
CONFIG_NSH_ARCHINIT=y |
||||
CONFIG_NSH_ARCHROMFS=y |
||||
CONFIG_NSH_ARGCAT=y |
||||
CONFIG_NSH_BUILTIN_APPS=y |
||||
CONFIG_NSH_CMDPARMS=y |
||||
CONFIG_NSH_CROMFSETC=y |
||||
CONFIG_NSH_DISABLE_IFCONFIG=y |
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y |
||||
CONFIG_NSH_DISABLE_MB=y |
||||
CONFIG_NSH_DISABLE_MH=y |
||||
CONFIG_NSH_DISABLE_TELNETD=y |
||||
CONFIG_NSH_LINELEN=128 |
||||
CONFIG_NSH_MAXARGUMENTS=12 |
||||
CONFIG_NSH_NESTDEPTH=8 |
||||
CONFIG_NSH_QUOTE=y |
||||
CONFIG_NSH_ROMFSETC=y |
||||
CONFIG_NSH_ROMFSSECTSIZE=128 |
||||
CONFIG_NSH_STRERROR=y |
||||
CONFIG_NSH_VARS=y |
||||
CONFIG_NXFONTS_DISABLE_16BPP=y |
||||
CONFIG_NXFONTS_DISABLE_1BPP=y |
||||
CONFIG_NXFONTS_DISABLE_24BPP=y |
||||
CONFIG_NXFONTS_DISABLE_2BPP=y |
||||
CONFIG_NXFONTS_DISABLE_32BPP=y |
||||
CONFIG_NXFONTS_DISABLE_4BPP=y |
||||
CONFIG_NXFONTS_DISABLE_8BPP=y |
||||
CONFIG_PIPES=y |
||||
CONFIG_PREALLOC_MQ_MSGS=4 |
||||
CONFIG_PREALLOC_TIMERS=50 |
||||
CONFIG_PREALLOC_WDOGS=50 |
||||
CONFIG_PRIORITY_INHERITANCE=y |
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y |
||||
CONFIG_PTHREAD_STACK_MIN=512 |
||||
CONFIG_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=1536 |
||||
CONFIG_SCHED_WAITPID=y |
||||
CONFIG_SDCLONE_DISABLE=y |
||||
CONFIG_SDMMC1_SDIO_MODE=y |
||||
CONFIG_SEM_NNESTPRIO=8 |
||||
CONFIG_SEM_PREALLOCHOLDERS=0 |
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y |
||||
CONFIG_SERIAL_TERMIOS=y |
||||
CONFIG_SIG_DEFAULT=y |
||||
CONFIG_SIG_SIGALRM_ACTION=y |
||||
CONFIG_SIG_SIGUSR1_ACTION=y |
||||
CONFIG_SIG_SIGUSR2_ACTION=y |
||||
CONFIG_SIG_SIGWORK=4 |
||||
CONFIG_STACK_COLORATION=y |
||||
CONFIG_START_DAY=30 |
||||
CONFIG_START_MONTH=11 |
||||
CONFIG_STDIO_BUFFER_SIZE=32 |
||||
CONFIG_STM32H7_ADC1=y |
||||
CONFIG_STM32H7_BBSRAM=y |
||||
CONFIG_STM32H7_BBSRAM_FILES=5 |
||||
CONFIG_STM32H7_BKPSRAM=y |
||||
CONFIG_STM32H7_DMA1=y |
||||
CONFIG_STM32H7_DMA2=y |
||||
CONFIG_STM32H7_DMACAPABLE=y |
||||
CONFIG_STM32H7_DTCMEXCLUDE=y |
||||
CONFIG_STM32H7_DTCM_PROCFS=y |
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y |
||||
CONFIG_STM32H7_I2C1=y |
||||
CONFIG_STM32H7_I2C2=y |
||||
CONFIG_STM32H7_I2C3=y |
||||
CONFIG_STM32H7_I2C4=y |
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y |
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 |
||||
CONFIG_STM32H7_OTGFS=y |
||||
CONFIG_STM32H7_PROGMEM=y |
||||
CONFIG_STM32H7_RTC=y |
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1 |
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y |
||||
CONFIG_STM32H7_SDMMC1=y |
||||
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y |
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y |
||||
CONFIG_STM32H7_SPI1=y |
||||
CONFIG_STM32H7_SPI2=y |
||||
CONFIG_STM32H7_SPI4=y |
||||
CONFIG_STM32H7_SPI5=y |
||||
CONFIG_STM32H7_SPI6=y |
||||
CONFIG_STM32H7_TIM1=y |
||||
CONFIG_STM32H7_TIM3=y |
||||
CONFIG_STM32H7_TIM4=y |
||||
CONFIG_STM32H7_UART4=y |
||||
CONFIG_STM32H7_UART7=y |
||||
CONFIG_STM32H7_UART8=y |
||||
CONFIG_STM32H7_USART1=y |
||||
CONFIG_STM32H7_USART2=y |
||||
CONFIG_STM32H7_USART3=y |
||||
CONFIG_STM32H7_USART6=y |
||||
CONFIG_STM32H7_USART_BREAKS=y |
||||
CONFIG_STM32H7_USART_INVERT=y |
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y |
||||
CONFIG_STM32H7_USART_SWAP=y |
||||
CONFIG_SYSTEM_CDCACM=y |
||||
CONFIG_SYSTEM_NSH=y |
||||
CONFIG_TASK_NAME_SIZE=24 |
||||
CONFIG_TIME_EXTENDED=y |
||||
CONFIG_TTY_SIGINT=y |
||||
CONFIG_TTY_SIGSTP=y |
||||
CONFIG_UART4_BAUD=57600 |
||||
CONFIG_UART4_DMA=y |
||||
CONFIG_UART4_RXBUFSIZE=600 |
||||
CONFIG_UART4_TXBUFSIZE=1500 |
||||
CONFIG_UART7_BAUD=57600 |
||||
CONFIG_UART7_RXBUFSIZE=600 |
||||
CONFIG_UART7_SERIAL_CONSOLE=y |
||||
CONFIG_UART7_TXBUFSIZE=1500 |
||||
CONFIG_UART8_BAUD=57600 |
||||
CONFIG_UART8_DMA=y |
||||
CONFIG_UART8_RXBUFSIZE=600 |
||||
CONFIG_UART8_TXBUFSIZE=1500 |
||||
CONFIG_USART1_BAUD=57600 |
||||
CONFIG_USART1_DMA=y |
||||
CONFIG_USART1_RXBUFSIZE=600 |
||||
CONFIG_USART1_TXBUFSIZE=1500 |
||||
CONFIG_USART2_BAUD=57600 |
||||
CONFIG_USART2_DMA=y |
||||
CONFIG_USART2_IFLOWCONTROL=y |
||||
CONFIG_USART2_OFLOWCONTROL=y |
||||
CONFIG_USART2_RXBUFSIZE=600 |
||||
CONFIG_USART2_TXBUFSIZE=1500 |
||||
CONFIG_USART3_BAUD=57600 |
||||
CONFIG_USART3_DMA=y |
||||
CONFIG_USART3_IFLOWCONTROL=y |
||||
CONFIG_USART3_OFLOWCONTROL=y |
||||
CONFIG_USART3_RXBUFSIZE=600 |
||||
CONFIG_USART3_TXBUFSIZE=3000 |
||||
CONFIG_USART6_BAUD=57600 |
||||
CONFIG_USART6_DMA=y |
||||
CONFIG_USART6_RXBUFSIZE=600 |
||||
CONFIG_USART6_TXBUFSIZE=1500 |
||||
CONFIG_USBDEV=y |
||||
CONFIG_USBDEV_BUSPOWERED=y |
||||
CONFIG_USBDEV_MAXPOWER=500 |
||||
CONFIG_USEC_PER_TICK=1000 |
||||
CONFIG_USERMAIN_STACKSIZE=2624 |
||||
CONFIG_USER_ENTRYPOINT="nsh_main" |
||||
CONFIG_WATCHDOG=y |
@ -0,0 +1,226 @@
@@ -0,0 +1,226 @@
|
||||
/**************************************************************************** |
||||
* scripts/script.ld |
||||
* |
||||
* Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. |
||||
* Author: Gregory Nutt <gnutt@nuttx.org> |
||||
* |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name NuttX nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory. |
||||
* The flash memory is partitioned into a User Flash memory and a System |
||||
* Flash memory. Each of these memories has two banks: |
||||
* |
||||
* 1) User Flash memory: |
||||
* |
||||
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each |
||||
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each |
||||
* |
||||
* 2) System Flash memory: |
||||
* |
||||
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector |
||||
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector |
||||
* |
||||
* 3) User option bytes for user configuration, only in Bank 1. |
||||
* |
||||
* In the STM32H743II, two different boot spaces can be selected through |
||||
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and |
||||
* BOOT_ADD1 option bytes: |
||||
* |
||||
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. |
||||
* ST programmed value: Flash memory at 0x0800:0000 |
||||
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. |
||||
* ST programmed value: System bootloader at 0x1FF0:0000 |
||||
* |
||||
* The Durandal has a Swtich on board, the BOOT0 pin is at ground so by default, |
||||
* the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is |
||||
* drepresed, then the boot will be from 0x1FF0:0000 |
||||
* |
||||
* The STM32H743ZI also has 1024Kb of data SRAM. |
||||
* SRAM is split up into several blocks and into three power domains: |
||||
* |
||||
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with |
||||
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus |
||||
* |
||||
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 |
||||
* |
||||
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit |
||||
* DTCM ports. The DTCM-RAM could be used for critical real-time |
||||
* data, such as interrupt service routines or stack / heap memory. |
||||
* Both DTCM-RAMs can be used in parallel (for load/store operations) |
||||
* thanks to the Cortex-M7 dual issue capability. |
||||
* |
||||
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 |
||||
* |
||||
* This RAM is connected to ITCM 64-bit interface designed for |
||||
* execution of critical real-times routines by the CPU. |
||||
* |
||||
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA |
||||
* through D1 domain AXI bus matrix |
||||
* |
||||
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000 |
||||
* |
||||
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA |
||||
* through D2 domain AHB bus matrix |
||||
* |
||||
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 |
||||
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 |
||||
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 |
||||
* |
||||
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 |
||||
* |
||||
* 4) AHB SRAM (D3 domain) accessible by most of system masters |
||||
* through D3 domain AHB bus matrix |
||||
* |
||||
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 |
||||
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 |
||||
* |
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 |
||||
* where the code expects to begin execution by jumping to the entry point in |
||||
* the 0x0800:0000 address range. |
||||
*/ |
||||
|
||||
MEMORY |
||||
{ |
||||
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K |
||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K |
||||
dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K |
||||
dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K |
||||
sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K |
||||
sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K |
||||
sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K |
||||
sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K |
||||
sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K |
||||
bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K |
||||
} |
||||
|
||||
OUTPUT_ARCH(arm) |
||||
EXTERN(_vectors) |
||||
ENTRY(_stext) |
||||
|
||||
/* |
||||
* Ensure that abort() is present in the final object. The exception handling |
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided). |
||||
*/ |
||||
EXTERN(abort) |
||||
EXTERN(_bootdelay_signature) |
||||
|
||||
SECTIONS |
||||
{ |
||||
.text : { |
||||
_stext = ABSOLUTE(.); |
||||
*(.vectors) |
||||
. = ALIGN(32); |
||||
/* |
||||
This signature provides the bootloader with a way to delay booting |
||||
*/ |
||||
_bootdelay_signature = ABSOLUTE(.); |
||||
FILL(0xffecc2925d7d05c5) |
||||
. += 8; |
||||
*(.text .text.*) |
||||
*(.fixup) |
||||
*(.gnu.warning) |
||||
*(.rodata .rodata.*) |
||||
*(.gnu.linkonce.t.*) |
||||
*(.glue_7) |
||||
*(.glue_7t) |
||||
*(.got) |
||||
*(.gcc_except_table) |
||||
*(.gnu.linkonce.r.*) |
||||
_etext = ABSOLUTE(.); |
||||
|
||||
/* |
||||
* This is a hack to make the newlib libm __errno() call |
||||
* use the NuttX get_errno_ptr() function. |
||||
*/ |
||||
__errno = get_errno_ptr; |
||||
} > flash |
||||
|
||||
/* |
||||
* Init functions (static constructors and the like) |
||||
*/ |
||||
.init_section : { |
||||
_sinit = ABSOLUTE(.); |
||||
KEEP(*(.init_array .init_array.*)) |
||||
_einit = ABSOLUTE(.); |
||||
} > flash |
||||
|
||||
/* |
||||
* Construction data for parameters. |
||||
*/ |
||||
__param ALIGN(4): { |
||||
__param_start = ABSOLUTE(.); |
||||
KEEP(*(__param*)) |
||||
__param_end = ABSOLUTE(.); |
||||
} > flash |
||||
|
||||
.ARM.extab : { |
||||
*(.ARM.extab*) |
||||
} > flash |
||||
|
||||
__exidx_start = ABSOLUTE(.); |
||||
.ARM.exidx : { |
||||
*(.ARM.exidx*) |
||||
} > flash |
||||
__exidx_end = ABSOLUTE(.); |
||||
|
||||
_eronly = ABSOLUTE(.); |
||||
|
||||
.data : { |
||||
_sdata = ABSOLUTE(.); |
||||
*(.data .data.*) |
||||
*(.gnu.linkonce.d.*) |
||||
CONSTRUCTORS |
||||
_edata = ABSOLUTE(.); |
||||
} > sram AT > flash |
||||
|
||||
.bss : { |
||||
_sbss = ABSOLUTE(.); |
||||
*(.bss .bss.*) |
||||
*(.gnu.linkonce.b.*) |
||||
*(COMMON) |
||||
. = ALIGN(4); |
||||
_ebss = ABSOLUTE(.); |
||||
} > sram |
||||
|
||||
/* Stabs debugging sections. */ |
||||
.stab 0 : { *(.stab) } |
||||
.stabstr 0 : { *(.stabstr) } |
||||
.stab.excl 0 : { *(.stab.excl) } |
||||
.stab.exclstr 0 : { *(.stab.exclstr) } |
||||
.stab.index 0 : { *(.stab.index) } |
||||
.stab.indexstr 0 : { *(.stab.indexstr) } |
||||
.comment 0 : { *(.comment) } |
||||
.debug_abbrev 0 : { *(.debug_abbrev) } |
||||
.debug_info 0 : { *(.debug_info) } |
||||
.debug_line 0 : { *(.debug_line) } |
||||
.debug_pubnames 0 : { *(.debug_pubnames) } |
||||
.debug_aranges 0 : { *(.debug_aranges) } |
||||
} |
@ -0,0 +1,53 @@
@@ -0,0 +1,53 @@
|
||||
############################################################################ |
||||
# |
||||
# 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 |
||||
init.c |
||||
led.c |
||||
manifest.c |
||||
sdio.c |
||||
spi.cpp |
||||
timer_config.c |
||||
usb.c |
||||
) |
||||
add_dependencies(drivers_board arch_board_hw_info) |
||||
|
||||
target_link_libraries(drivers_board |
||||
PRIVATE |
||||
arch_board_hw_info |
||||
drivers__led # drv_led_start |
||||
nuttx_arch # sdio |
||||
nuttx_drivers # sdio |
||||
px4_layer |
||||
) |
@ -0,0 +1,609 @@
@@ -0,0 +1,609 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 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 board_config.h |
||||
* |
||||
* holybro durandal-v1 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 |
||||
****************************************************************************************************/ |
||||
|
||||
/* PX4IO connection configuration */ |
||||
|
||||
#define BOARD_USES_PX4IO_VERSION 2 |
||||
#define PX4IO_SERIAL_DEVICE "/dev/ttyS6" |
||||
#define PX4IO_SERIAL_TX_GPIO GPIO_UART8_TX |
||||
#define PX4IO_SERIAL_RX_GPIO GPIO_UART8_RX |
||||
#define PX4IO_SERIAL_BASE STM32_UART8_BASE |
||||
#define PX4IO_SERIAL_VECTOR STM32_IRQ_UART8 |
||||
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_UART8_TX |
||||
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_UART8_RX |
||||
#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB1LENR |
||||
#define PX4IO_SERIAL_RCC_EN RCC_APB1LENR_UART8EN |
||||
#define PX4IO_SERIAL_CLOCK STM32_PCLK1_FREQUENCY |
||||
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ |
||||
|
||||
/* Configuration ************************************************************************************/ |
||||
|
||||
# define BOARD_HAS_LTC44XX_VALIDS 2 // No LTC or N Bricks
|
||||
# define BOARD_HAS_USB_VALID 1 // LTC Has No USB valid
|
||||
# define BOARD_HAS_NBAT_V 2 // Only one Vbat to ADC
|
||||
# define BOARD_HAS_NBAT_I 2 // No Ibat ADC
|
||||
|
||||
/* Holybro Durandal V1 GPIOs ************************************************************************/ |
||||
|
||||
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ |
||||
|
||||
#define GPIO_nLED_RED /* PB1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1) |
||||
#define GPIO_nLED_GREEN /* PC6 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN6) |
||||
#define GPIO_nLED_BLUE /* PC7 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7) |
||||
|
||||
#define BOARD_HAS_CONTROL_STATUS_LEDS 1 |
||||
#define BOARD_OVERLOAD_LED LED_RED |
||||
#define BOARD_ARMED_STATE_LED LED_BLUE |
||||
|
||||
/* SENSORS are on SPI1, 5, 6
|
||||
* MEMORY is on bus SPI2 |
||||
* MS5611 is on bus SPI4 |
||||
*/ |
||||
|
||||
#define PX4_SPI_BUS_SENSORS 1 |
||||
#define PX4_SPI_BUS_SENSORS3 PX4_SPI_BUS_SENSORS // for BMI088
|
||||
#define PX4_SPI_BUS_MEMORY 2 |
||||
#define PX4_SPI_BUS_BARO 4 |
||||
#define PX4_SPI_BUS_EXTERNAL1 5 |
||||
#define PX4_SPI_BUS_EXTERNAL2 6 |
||||
|
||||
/* Define the Chip Selects, Data Ready and Control signals per SPI bus */ |
||||
|
||||
/* SPI 1 CS */ |
||||
|
||||
#define GPIO_SPI1_CS1_ICM20689 /* PF2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN2) |
||||
#define GPIO_SPI1_CS3_BMI088_GYRO /* PF4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN4) |
||||
#define GPIO_SPI1_CS4_BMI088_ACC /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) |
||||
#define GPIO_SPI1_CS5_AUX_MEM /* PH5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5) |
||||
|
||||
|
||||
/* Define the SPI1 Data Ready interrupts */ |
||||
|
||||
#define GPIO_SPI1_DRDY1_ICM20689 /* PB4 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN4) |
||||
#define GPIO_SPI1_DRDY2_BMI088_GYRO /* PB14 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN14) |
||||
#define GPIO_SPI1_DRDY3_BMI088_ACC /* PB15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN15) |
||||
#define GPIO_SPI1_DRDY5_BMI088_GYRO /* PC13 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN13) |
||||
#define GPIO_SPI1_DRDY6_BMI088_ACC /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN10) |
||||
|
||||
/* SPI1 off */ |
||||
|
||||
#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) |
||||
#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) |
||||
#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) |
||||
|
||||
#define GPIO_DRDY_OFF_SPI1_DRDY1_ICM20689 _PIN_OFF(GPIO_SPI1_DRDY1_ICM20689) |
||||
#define GPIO_DRDY_OFF_SPI1_DRDY2_BMI088_GYRO _PIN_OFF(GPIO_SPI1_DRDY2_BMI088_GYRO) |
||||
#define GPIO_DRDY_OFF_SPI1_DRDY3_BMI088_ACC _PIN_OFF(GPIO_SPI1_DRDY3_BMI088_ACC) |
||||
#define GPIO_DRDY_OFF_SPI1_DRDY5_BMI088_GYRO _PIN_OFF(GPIO_SPI1_DRDY5_BMI088_GYRO) |
||||
#define GPIO_DRDY_OFF_SPI1_DRDY6_BMI088_ACC _PIN_OFF(GPIO_SPI1_DRDY6_BMI088_ACC) |
||||
|
||||
/* SPI 2 CS */ |
||||
|
||||
#define GPIO_SPI2_CS_FRAM /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN5) |
||||
|
||||
/* SPI 4 CS */ |
||||
|
||||
#define GPIO_SPI4_CS1_MS5611 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN10) |
||||
|
||||
/* SPI 5 CS */ |
||||
|
||||
#define SPI5_CS1_EXTERNAL1 /* PI4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN4) |
||||
#define SPI5_CS2_EXTERNAL1 /* PI10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN10) |
||||
|
||||
/* Define the SPI1 Data Ready and Control signals */ |
||||
|
||||
#define GPIO_SPI5_DRDY7_EXTERNAL1 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) |
||||
|
||||
/* SPI 6 */ |
||||
|
||||
#define SPI6_CS1_EXTERNAL2 /* PI6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN6) |
||||
#define SPI6_CS2_EXTERNAL2 /* PI7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN7) |
||||
#define SPI6_CS3_EXTERNAL2 /* PI8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN8) |
||||
|
||||
/*
|
||||
* Define the ability to shut off off the sensor signals |
||||
* by changing the signals to inputs |
||||
*/ |
||||
|
||||
#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) |
||||
|
||||
|
||||
#define GPIO_DRDY_OFF_SPI5_DRDY7_EXTERNAL1 _PIN_OFF(GPIO_SPI5_DRDY7_EXTERNAL1) |
||||
|
||||
|
||||
/* v BEGIN Legacy SPI defines TODO: fix this with enumeration */ |
||||
#define PX4_SPI_BUS_RAMTRON PX4_SPI_BUS_MEMORY |
||||
/* ^ END Legacy SPI defines TODO: fix this with enumeration */ |
||||
|
||||
#define PX4_SPIDEV_ICM_20689 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,0) |
||||
#define PX4_SPIDEV_BMI088_GYR PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,1) |
||||
#define PX4_SPIDEV_BMI088_ACC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,2) |
||||
#define PX4_SPIDEV_AUX_MEM PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,3) |
||||
#define PX4_SENSOR_BUS_CS_GPIO {GPIO_SPI1_CS1_ICM20689, GPIO_SPI1_CS3_BMI088_GYRO, GPIO_SPI1_CS4_BMI088_ACC, GPIO_SPI1_CS5_AUX_MEM} |
||||
|
||||
#define PX4_SPIDEV_MEMORY PX4_MK_SPI_SEL(PX4_SPI_BUS_MEMORY,0) |
||||
#define PX4_MEMORY_BUS_CS_GPIO {GPIO_SPI2_CS_FRAM} |
||||
|
||||
#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_BARO,0) |
||||
#define PX4_BARO_BUS_CS_GPIO {GPIO_SPI4_CS1_MS5611} |
||||
|
||||
#define PX4_SPIDEV_EXTERNAL1_1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1,0) |
||||
#define PX4_SPIDEV_EXTERNAL1_2 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1,1) |
||||
#define PX4_EXTERNAL1_BUS_CS_GPIO {SPI5_CS1_EXTERNAL1, SPI5_CS2_EXTERNAL1} |
||||
|
||||
#define PX4_SPIDEV_EXTERNAL2_1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2,0) |
||||
#define PX4_SPIDEV_EXTERNAL2_2 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2,1) |
||||
#define PX4_SPIDEV_EXTERNAL2_3 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2,2) |
||||
#define PX4_EXTERNAL2_BUS_CS_GPIO {SPI6_CS1_EXTERNAL2, SPI6_CS2_EXTERNAL2, SPI6_CS3_EXTERNAL2} |
||||
|
||||
|
||||
/* I2C busses */ |
||||
|
||||
#define PX4_I2C_BUS_EXPANSION 1 |
||||
#define PX4_I2C_BUS_EXPANSION1 2 |
||||
#define PX4_I2C_BUS_ONBOARD 3 |
||||
#define PX4_I2C_BUS_EXPANSION2 4 |
||||
#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION |
||||
|
||||
#define BOARD_NUMBER_I2C_BUSES 4 |
||||
#define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000, 100000} |
||||
|
||||
/*
|
||||
* ADC channels |
||||
* |
||||
* These are the channel numbers of the ADCs of the microcontroller that |
||||
* can be used by the Px4 Firmware in the adc driver |
||||
*/ |
||||
|
||||
/* ADC defines to be used in sensors.cpp to read from a particular channel */ |
||||
|
||||
#define ADC1_CH(n) (n) |
||||
|
||||
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ |
||||
|
||||
#define PX4_ADC_GPIO \ |
||||
/* PA0 */ GPIO_ADC1_INP16, \
|
||||
/* PA1 */ GPIO_ADC1_INP17, \
|
||||
/* PA2 */ GPIO_ADC12_INP14, \
|
||||
/* PA3 */ GPIO_ADC12_INP15, \
|
||||
/* PA4 */ GPIO_ADC12_INP18, \
|
||||
/* PB0 */ GPIO_ADC12_INP9, \
|
||||
/* PC0 */ GPIO_ADC123_INP10, \
|
||||
/* PC1 */ GPIO_ADC123_INP11, \
|
||||
/* PC2 */ GPIO_ADC123_INP12, \
|
||||
/* PC3 */ GPIO_ADC12_INP13, \
|
||||
/* PC4 */ GPIO_ADC12_INP4 |
||||
|
||||
/* Define Channel numbers must match above GPIO pin IN(n)*/ |
||||
|
||||
#define ADC_BATTERY1_VOLTAGE_CHANNEL /* PA0 */ ADC1_CH(16) |
||||
#define ADC_BATTERY1_CURRENT_CHANNEL /* PA1 */ ADC1_CH(17) |
||||
#define ADC_BATTERY2_VOLTAGE_CHANNEL /* PA2 */ ADC1_CH(14) |
||||
#define ADC_BATTERY2_CURRENT_CHANNEL /* PA3 */ ADC1_CH(15) |
||||
#define ADC1_6V6_IN_CHANNEL /* PA4 */ ADC1_CH(18) |
||||
#define ADC_RSSI_IN_CHANNEL /* PB0 */ ADC1_CH(9) |
||||
#define ADC_SCALED_V5_CHANNEL /* PC0 */ ADC1_CH(10) |
||||
#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL /* PC1 */ ADC1_CH(11) |
||||
#define ADC_HW_VER_SENSE_CHANNEL /* PC2 */ ADC1_CH(12) |
||||
#define ADC_HW_REV_SENSE_CHANNEL /* PC3 */ ADC1_CH(13) |
||||
#define ADC1_3V3_IN_CHANNEL /* PC4 */ ADC1_CH(4) |
||||
|
||||
#define ADC_CHANNELS \ |
||||
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
|
||||
(1 << ADC1_6V6_IN_CHANNEL) | \
|
||||
(1 << ADC_RSSI_IN_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
|
||||
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
|
||||
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
|
||||
(1 << ADC1_3V3_IN_CHANNEL)) |
||||
|
||||
/* Define Battery 1 Voltage Divider and A per V
|
||||
*/ |
||||
|
||||
#define BOARD_BATTERY1_V_DIV (18.1f) /* measured with the provided PM board */ |
||||
#define BOARD_BATTERY1_A_PER_V (36.367515152f) |
||||
|
||||
/* HW has to large of R termination on ADC todo:change when HW value is chosen */ |
||||
|
||||
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) |
||||
|
||||
/* HW Version and Revision drive signals Default to 1 to detect */ |
||||
|
||||
#define BOARD_HAS_HW_VERSIONING |
||||
|
||||
#define GPIO_HW_REV_DRIVE /* PH14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN14) |
||||
#define GPIO_HW_REV_SENSE /* PC3 */ GPIO_ADC12_INP13 |
||||
#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) |
||||
#define GPIO_HW_VER_SENSE /* PC2 */ GPIO_ADC123_INP12 |
||||
#define HW_INFO_INIT {'V','D','x', 'x',0} |
||||
#define HW_INFO_INIT_VER 2 |
||||
#define HW_INFO_INIT_REV 3 |
||||
|
||||
/* CAN Silence
|
||||
* |
||||
* Silent mode control \ ESC Mux select |
||||
*/ |
||||
|
||||
#define GPIO_CAN1_SILENT_S0 /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) |
||||
#define GPIO_CAN2_SILENT_S1 /* PH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN3) |
||||
|
||||
/* HEATER
|
||||
* PWM in future |
||||
*/ |
||||
#define GPIO_HEATER_OUTPUT /* PA7 T14CH1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7) |
||||
|
||||
/* PWM Capture
|
||||
* |
||||
* 6 PWM Capture inputs are configured. |
||||
* |
||||
* Pins: |
||||
* |
||||
* FMU_CAP1 : PB11 : TIM2_CH4 |
||||
* FMU_CAP2 : PB3 : TIM2_CH2 |
||||
* FMU_CAP3 : PA5 : TIM2_CH1 |
||||
* FMU_CAP4 : PH9 : TIM12_CH2 |
||||
* FMU_CAP5 : PH6 : TIM12_CH1 |
||||
* FMU_CAP6 : PD14 : TIM4_CH3 |
||||
*/ |
||||
|
||||
#define GPIO_TIM2_CH4_IN /* PB11 FMU_CAP3 */ GPIO_TIM2_CH4IN_2 |
||||
#define GPIO_TIM2_CH2_IN /* PB3 FMU_CAP2 */ GPIO_TIM2_CH2IN_2 |
||||
#define GPIO_TIM2_CH1_IN /* PA5 FMU_CAP1 */ GPIO_TIM2_CH1IN_3 |
||||
#define GPIO_TIM12_CH2_IN /* PH9 FMU_CAP4 */ GPIO_TIM12_CH2IN_2 |
||||
#define GPIO_TIM12_CH1_IN /* PH6 FMU_CAP5 */ GPIO_TIM12_CH1IN_2 |
||||
#define GPIO_TIM4_CH3_IN /* PD14 FMU_CAP6 */ GPIO_TIM4_CH3IN_2 |
||||
|
||||
#define DIRECT_PWM_CAPTURE_CHANNELS 6 |
||||
|
||||
/* PWM
|
||||
* |
||||
* 5 PWM outputs are configured. |
||||
* |
||||
* Pins: |
||||
* |
||||
* FMU_CH1 : PE14 : TIM1_CH4 |
||||
* FMU_CH2 : PA10 : TIM1_CH3 |
||||
* FMU_CH3 : PE11 : TIM1_CH2 |
||||
* FMU_CH4 : PE9 : TIM1_CH1 |
||||
* FMU_CH5 : PD13 : TIM4_CH2 |
||||
* |
||||
*/ |
||||
#define GPIO_TIM4_CH2OUT /* PD13 T4C2 FMU5 */ GPIO_TIM4_CH2OUT_2 |
||||
#define GPIO_TIM1_CH1OUT /* PE9 T1C1 FMU4 */ GPIO_TIM1_CH1OUT_2 |
||||
#define GPIO_TIM1_CH2OUT /* PE11 T1C2 FMU3 */ GPIO_TIM1_CH2OUT_2 |
||||
#define GPIO_TIM1_CH3OUT /* PA10 T1C3 FMU2 */ GPIO_TIM1_CH3OUT_1 |
||||
#define GPIO_TIM1_CH4OUT /* PE14 T1C4 FMU1 */ GPIO_TIM1_CH4OUT_2 |
||||
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 5 |
||||
|
||||
#define GPIO_TIM4_CH2IN /* PD13 T4C2 FMU5 */ GPIO_TIM4_CH2IN_2 |
||||
#define GPIO_TIM1_CH1IN /* PE9 T1C1 FMU4 */ GPIO_TIM1_CH1IN_2 |
||||
#define GPIO_TIM1_CH2IN /* PE11 T1C2 FMU3 */ GPIO_TIM1_CH2IN_2 |
||||
#define GPIO_TIM1_CH3IN /* PA10 T1C3 FMU2 */ GPIO_TIM1_CH3IN_1 |
||||
#define GPIO_TIM1_CH4IN /* PE14 T1C4 FMU1 */ GPIO_TIM1_CH4IN_2 |
||||
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 5 |
||||
|
||||
/* User GPIOs
|
||||
* |
||||
* GPIO0-4 are the PWM servo outputs. |
||||
*/ |
||||
|
||||
#define _MK_GPIO_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLUP)) |
||||
|
||||
#define GPIO_GPIO4_INPUT /* PD13 T4C2 FMU5 */ _MK_GPIO_INPUT(GPIO_TIM4_CH2IN) |
||||
#define GPIO_GPIO3_INPUT /* PE9 T1C1 FMU4 */ _MK_GPIO_INPUT(GPIO_TIM1_CH1IN) |
||||
#define GPIO_GPIO2_INPUT /* PE11 T1C2 FMU3 */ _MK_GPIO_INPUT(GPIO_TIM1_CH2IN) |
||||
#define GPIO_GPIO1_INPUT /* PA10 T1C3 FMU2 */ _MK_GPIO_INPUT(GPIO_TIM1_CH3IN) |
||||
#define GPIO_GPIO0_INPUT /* PE14 T1C4 FMU1 */ _MK_GPIO_INPUT(GPIO_TIM1_CH4IN) |
||||
|
||||
#define _MK_GPIO_OUTPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR)) |
||||
|
||||
#define GPIO_GPIO4_OUTPUT /* PD13 T4C2 FMU5 */ _MK_GPIO_OUTPUT(GPIO_TIM4_CH2OUT) |
||||
#define GPIO_GPIO3_OUTPUT /* PE9 T1C1 FMU4 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH1OUT) |
||||
#define GPIO_GPIO2_OUTPUT /* PE11 T1C2 FMU3 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH2OUT) |
||||
#define GPIO_GPIO1_OUTPUT /* PA10 T1C3 FMU2 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH3OUT) |
||||
#define GPIO_GPIO0_OUTPUT /* PE14 T1C4 FMU1 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH4OUT) |
||||
|
||||
|
||||
/* Power supply control and monitoring GPIOs */ |
||||
|
||||
#define GPIO_nPOWER_IN_A /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1) |
||||
#define GPIO_nPOWER_IN_B /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2) |
||||
#define GPIO_nPOWER_IN_C /* PG3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN3) |
||||
|
||||
#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */ |
||||
#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */ |
||||
#define BOARD_NUMBER_BRICKS 2 |
||||
#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */ |
||||
|
||||
#define GPIO_nVDD_5V_PERIPH_EN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) |
||||
#define GPIO_nVDD_5V_PERIPH_OC /* PE15 */ (GPIO_INPUT |GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15) |
||||
#define GPIO_nVDD_5V_HIPOWER_EN /* PF12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN12) |
||||
#define GPIO_nVDD_5V_HIPOWER_OC /* PG13 */ (GPIO_INPUT |GPIO_PULLUP|GPIO_PORTF|GPIO_PIN13) |
||||
#define GPIO_VDD_3V3_SENSORS_EN /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN3) |
||||
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4) |
||||
#define GPIO_VDD_3V3_SD_CARD_EN /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN7) |
||||
|
||||
|
||||
/* 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_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_HIPOWER_EN, !(on_true)) |
||||
#define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, (on_true)) |
||||
#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true)) |
||||
#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) |
||||
#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) |
||||
|
||||
/* Tone alarm output */ |
||||
|
||||
#define TONE_ALARM_TIMER 15 /* timer 15 */ |
||||
#define TONE_ALARM_CHANNEL 1 /* PE5 TIM15_CH1 */ |
||||
|
||||
#define GPIO_BUZZER_1 /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN5) |
||||
|
||||
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 |
||||
#define GPIO_TONE_ALARM GPIO_TIM15_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 */ |
||||
|
||||
/* RC Serial port */ |
||||
|
||||
/* Input Capture Channels. */ |
||||
|
||||
#define INPUT_CAP1_TIMER 2 |
||||
#define INPUT_CAP1_CHANNEL /* T2C4 */ 4 |
||||
#define GPIO_INPUT_CAP1 /* PB11 */ GPIO_TIM2_CH4_IN |
||||
|
||||
#define INPUT_CAP2_TIMER 2 |
||||
#define INPUT_CAP2_CHANNEL /* T2C2 */ 2 |
||||
#define GPIO_INPUT_CAP2 /* PB3 */ GPIO_TIM2_CH2_IN |
||||
|
||||
#define INPUT_CAP3_TIMER 2 |
||||
#define INPUT_CAP3_CHANNEL /* T2C1 */ 1 |
||||
#define GPIO_INPU3_CAP1 /* PA5 */ GPIO_TIM2_CH1_IN |
||||
|
||||
#define INPUT_CAP4_TIMER 12 |
||||
#define INPUT_CAP4_CHANNEL /* T12C2*/ 2 |
||||
#define GPIO_INPUT_CAP4 /* PH9 */ GPIO_TIM12_CH2_IN |
||||
|
||||
#define INPUT_CAP5_TIMER 12 |
||||
#define INPUT_CAP5_CHANNEL /* T12C1*/ 1 |
||||
#define GPIO_INPUT_CAP5 /* PH6 */ GPIO_TIM12_CH1_IN |
||||
|
||||
#define INPUT_CAP6_TIMER 4 |
||||
#define INPUT_CAP6_CHANNEL /* T4C3 */ 3 |
||||
#define GPIO_INPUT_CAP6 /* PD14 */ GPIO_TIM4_CH3_IN |
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ |
||||
|
||||
#define PWMIN_TIMER 4 |
||||
#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2 |
||||
#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN |
||||
|
||||
/* RSSI_IN is grounded via a 10K */ |
||||
|
||||
#define GPIO_RSSI_IN /* PB0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN0) |
||||
|
||||
/* Safety Switch is only on PX4IO */ |
||||
|
||||
#define GPIO_nSAFETY_SWITCH_LED_OUT /* PE12 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN12) |
||||
#define GPIO_SAFETY_SWITCH_IN /* PE10 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN10) |
||||
|
||||
/* Power switch controls ******************************************************/ |
||||
|
||||
#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true) |
||||
|
||||
#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)) |
||||
|
||||
/* Board never powers off the Servo rail */ |
||||
|
||||
#define BOARD_ADC_SERVO_VALID (1) |
||||
|
||||
#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 |
||||
|
||||
/* The list of GPIO that will be initialized */ |
||||
|
||||
#define PX4_GPIO_PWM_INIT_LIST { \ |
||||
GPIO_GPIO4_INPUT, \
|
||||
GPIO_GPIO3_INPUT, \
|
||||
GPIO_GPIO2_INPUT, \
|
||||
GPIO_GPIO1_INPUT, \
|
||||
GPIO_GPIO0_INPUT, \
|
||||
} |
||||
|
||||
#define PX4_GPIO_INIT_LIST { \ |
||||
PX4_ADC_GPIO, \
|
||||
GPIO_HW_REV_DRIVE, \
|
||||
GPIO_HW_VER_DRIVE, \
|
||||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN2_TX, \
|
||||
GPIO_CAN2_RX, \
|
||||
GPIO_CAN1_SILENT_S0, \
|
||||
GPIO_CAN2_SILENT_S1, \
|
||||
GPIO_HEATER_OUTPUT, \
|
||||
GPIO_nPOWER_IN_A, \
|
||||
GPIO_nPOWER_IN_B, \
|
||||
GPIO_nPOWER_IN_C, \
|
||||
GPIO_nVDD_5V_PERIPH_EN, \
|
||||
GPIO_nVDD_5V_PERIPH_OC, \
|
||||
GPIO_nVDD_5V_HIPOWER_EN, \
|
||||
GPIO_nVDD_5V_HIPOWER_OC, \
|
||||
GPIO_VDD_3V3_SENSORS_EN, \
|
||||
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
|
||||
GPIO_VDD_3V3_SD_CARD_EN, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_RSSI_IN, \
|
||||
GPIO_nSAFETY_SWITCH_LED_OUT, \
|
||||
GPIO_SAFETY_SWITCH_IN, \
|
||||
} |
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER |
||||
|
||||
__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 Holybro Durandal V1 |
||||
* board. |
||||
* |
||||
****************************************************************************************************/ |
||||
|
||||
extern void stm32_spiinitialize(void); |
||||
|
||||
void board_spi_reset(int ms); |
||||
|
||||
extern void stm32_usbinitialize(void); |
||||
|
||||
extern void board_peripheral_reset(int ms); |
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize |
||||
* |
||||
* Description: |
||||
* Perform architecture specific initialization for NSH. |
||||
* |
||||
* CONFIG_NSH_ARCHINIT=y : |
||||
* Called from the NSH library |
||||
* |
||||
* CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, && |
||||
* CONFIG_NSH_ARCHINIT=n : |
||||
* Called from board_initialize(). |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#ifdef CONFIG_NSH_LIBRARY |
||||
int nsh_archinitialize(void); |
||||
#endif |
||||
|
||||
#include <px4_platform_common/board_common.h> |
||||
|
||||
#endif /* __ASSEMBLY__ */ |
||||
|
||||
__END_DECLS |
@ -0,0 +1,128 @@
@@ -0,0 +1,128 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 px4fmu_can.c |
||||
* |
||||
* Board-specific CAN functions. |
||||
*/ |
||||
|
||||
#ifdef CONFIG_CAN |
||||
|
||||
#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,278 @@
@@ -0,0 +1,278 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 |
||||
* nsh_archinitialize() 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 <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 |
||||
****************************************************************************/ |
||||
|
||||
/* 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_SENSORS_EN(false); |
||||
|
||||
bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN(); |
||||
/* Keep Spektum on to discharge rail*/ |
||||
VDD_3V3_SPEKTRUM_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_3V3_SPEKTRUM_POWER_EN(last); |
||||
VDD_3V3_SENSORS_EN(true); |
||||
VDD_5V_PERIPH_EN(true); |
||||
|
||||
} |
||||
|
||||
/************************************************************************************
|
||||
* Name: board_on_reset |
||||
* |
||||
* Description: |
||||
* Optionally provided function called on entry to board_system_reset |
||||
* It should perform any house keeping prior to the rest. |
||||
* |
||||
* status - 1 if resetting to boot loader |
||||
* 0 if just resetting |
||||
* |
||||
************************************************************************************/ |
||||
__EXPORT void board_on_reset(int status) |
||||
{ |
||||
/* configure the GPIO pins to outputs and keep them low */ |
||||
|
||||
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST; |
||||
px4_gpio_init(gpio, arraySize(gpio)); |
||||
|
||||
if (status >= 0) { |
||||
up_mdelay(6); |
||||
} |
||||
} |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize |
||||
* |
||||
* Description: |
||||
* All STM32 architectures must provide the following entry point. This entry point |
||||
* is called early in the initialization -- after all memory has been configured |
||||
* and mapped but before any devices have been initialized. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void |
||||
stm32_boardinitialize(void) |
||||
{ |
||||
board_on_reset(-1); /* Reset PWM first thing */ |
||||
|
||||
/* configure LEDs */ |
||||
|
||||
board_autoled_initialize(); |
||||
|
||||
/* configure pins */ |
||||
|
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST; |
||||
px4_gpio_init(gpio, arraySize(gpio)); |
||||
|
||||
/* configure SPI interfaces */ |
||||
|
||||
stm32_spiinitialize(); |
||||
|
||||
/* configure USB interfaces */ |
||||
|
||||
stm32_usbinitialize(); |
||||
|
||||
} |
||||
|
||||
/****************************************************************************
|
||||
* 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_3V3_SD_CARD_EN(true); |
||||
VDD_5V_PERIPH_EN(true); |
||||
VDD_5V_HIPOWER_EN(true); |
||||
VDD_3V3_SENSORS_EN(true); |
||||
VDD_3V3_SPEKTRUM_POWER_EN(true); |
||||
|
||||
/* Need hrt running before using the ADC */ |
||||
|
||||
px4_platform_init(); |
||||
|
||||
|
||||
if (OK == board_determine_hw_info()) { |
||||
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(), |
||||
board_get_hw_type_name()); |
||||
|
||||
} else { |
||||
syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n"); |
||||
} |
||||
|
||||
/* configure the DMA allocator */ |
||||
|
||||
if (board_dma_alloc_init() < 0) { |
||||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); |
||||
} |
||||
|
||||
#if 0 // serial DMA is not yet implemented in NuttX for stm32h7
|
||||
/* set up the serial DMA polling */ |
||||
static struct hrt_call serial_dma_call; |
||||
struct timespec ts; |
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered |
||||
* a DMA event. |
||||
*/ |
||||
ts.tv_sec = 0; |
||||
ts.tv_nsec = 1000000; |
||||
|
||||
hrt_call_every(&serial_dma_call, |
||||
ts_to_abstime(&ts), |
||||
ts_to_abstime(&ts), |
||||
(hrt_callout)stm32_serial_dma_poll, |
||||
NULL); |
||||
#endif |
||||
|
||||
|
||||
/* initial LED state */ |
||||
drv_led_start(); |
||||
led_off(LED_RED); |
||||
led_on(LED_GREEN); // Indicate Power.
|
||||
led_off(LED_BLUE); |
||||
|
||||
if (board_hardfault_init(2, true) != 0) { |
||||
led_on(LED_RED); |
||||
} |
||||
|
||||
#ifdef CONFIG_MMCSD |
||||
int ret = stm32_sdio_initialize(); |
||||
|
||||
if (ret != OK) { |
||||
led_on(LED_RED); |
||||
return ret; |
||||
} |
||||
|
||||
#endif /* CONFIG_MMCSD */ |
||||
|
||||
return OK; |
||||
} |
@ -0,0 +1,235 @@
@@ -0,0 +1,235 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 px4fmu2_led.c |
||||
* |
||||
* PX4FMU LED backend. |
||||
*/ |
||||
|
||||
#include <px4_platform_common/px4_config.h> |
||||
|
||||
#include <stdbool.h> |
||||
|
||||
#include "chip.h" |
||||
#include "stm32_gpio.h" |
||||
#include "board_config.h" |
||||
|
||||
#include <nuttx/board.h> |
||||
#include <arch/board/board.h> |
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h, |
||||
* but since we want to be able to disable the NuttX use |
||||
* of leds for system indication at will and there is no |
||||
* separate switch, we need to build independent of the |
||||
* CONFIG_ARCH_LEDS configuration switch. |
||||
*/ |
||||
__BEGIN_DECLS |
||||
extern void led_init(void); |
||||
extern void led_on(int led); |
||||
extern void led_off(int led); |
||||
extern void led_toggle(int led); |
||||
__END_DECLS |
||||
|
||||
#ifdef CONFIG_ARCH_LEDS |
||||
static bool nuttx_owns_leds = true; |
||||
// B R S G
|
||||
// 0 1 2 3
|
||||
static const uint8_t xlatpx4[] = {1, 2, 4, 0}; |
||||
# define xlat(p) xlatpx4[(p)] |
||||
static uint32_t g_ledmap[] = { |
||||
GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN
|
||||
GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE
|
||||
GPIO_nLED_RED, // Indexed by BOARD_LED_RED
|
||||
GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4
|
||||
}; |
||||
|
||||
#else |
||||
|
||||
# define xlat(p) (p) |
||||
static uint32_t g_ledmap[] = { |
||||
GPIO_nLED_BLUE, // Indexed by LED_BLUE
|
||||
GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER
|
||||
0, // Indexed by LED_SAFETY (defaulted to an input)
|
||||
GPIO_nLED_GREEN, // Indexed by LED_GREEN
|
||||
}; |
||||
|
||||
#endif |
||||
|
||||
__EXPORT void led_init(void) |
||||
{ |
||||
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { |
||||
if (g_ledmap[l] != 0) { |
||||
stm32_configgpio(g_ledmap[l]); |
||||
} |
||||
} |
||||
} |
||||
|
||||
static void phy_set_led(int led, bool state) |
||||
{ |
||||
/* Drive Low to switch on */ |
||||
|
||||
if (g_ledmap[led] != 0) { |
||||
stm32_gpiowrite(g_ledmap[led], !state); |
||||
} |
||||
} |
||||
|
||||
static bool phy_get_led(int led) |
||||
{ |
||||
/* If Low it is on */ |
||||
if (g_ledmap[led] != 0) { |
||||
return !stm32_gpioread(g_ledmap[led]); |
||||
} |
||||
|
||||
return false; |
||||
} |
||||
|
||||
__EXPORT void led_on(int led) |
||||
{ |
||||
phy_set_led(xlat(led), true); |
||||
} |
||||
|
||||
__EXPORT void led_off(int led) |
||||
{ |
||||
phy_set_led(xlat(led), false); |
||||
} |
||||
|
||||
__EXPORT void led_toggle(int led) |
||||
{ |
||||
phy_set_led(xlat(led), !phy_get_led(xlat(led))); |
||||
} |
||||
|
||||
#ifdef CONFIG_ARCH_LEDS |
||||
/****************************************************************************
|
||||
* Public Functions |
||||
****************************************************************************/ |
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_initialize |
||||
****************************************************************************/ |
||||
|
||||
void board_autoled_initialize(void) |
||||
{ |
||||
led_init(); |
||||
} |
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_on |
||||
****************************************************************************/ |
||||
|
||||
void board_autoled_on(int led) |
||||
{ |
||||
if (!nuttx_owns_leds) { |
||||
return; |
||||
} |
||||
|
||||
switch (led) { |
||||
default: |
||||
break; |
||||
|
||||
case LED_HEAPALLOCATE: |
||||
phy_set_led(BOARD_LED_BLUE, true); |
||||
break; |
||||
|
||||
case LED_IRQSENABLED: |
||||
phy_set_led(BOARD_LED_BLUE, false); |
||||
phy_set_led(BOARD_LED_GREEN, true); |
||||
break; |
||||
|
||||
case LED_STACKCREATED: |
||||
phy_set_led(BOARD_LED_GREEN, true); |
||||
phy_set_led(BOARD_LED_BLUE, true); |
||||
break; |
||||
|
||||
case LED_INIRQ: |
||||
phy_set_led(BOARD_LED_BLUE, true); |
||||
break; |
||||
|
||||
case LED_SIGNAL: |
||||
phy_set_led(BOARD_LED_GREEN, true); |
||||
break; |
||||
|
||||
case LED_ASSERTION: |
||||
phy_set_led(BOARD_LED_RED, true); |
||||
phy_set_led(BOARD_LED_BLUE, true); |
||||
break; |
||||
|
||||
case LED_PANIC: |
||||
phy_set_led(BOARD_LED_RED, true); |
||||
break; |
||||
|
||||
case LED_IDLE : /* IDLE */ |
||||
phy_set_led(BOARD_LED_RED, true); |
||||
break; |
||||
} |
||||
} |
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_off |
||||
****************************************************************************/ |
||||
|
||||
void board_autoled_off(int led) |
||||
{ |
||||
if (!nuttx_owns_leds) { |
||||
return; |
||||
} |
||||
|
||||
switch (led) { |
||||
default: |
||||
break; |
||||
|
||||
case LED_SIGNAL: |
||||
phy_set_led(BOARD_LED_GREEN, false); |
||||
break; |
||||
|
||||
case LED_INIRQ: |
||||
phy_set_led(BOARD_LED_BLUE, false); |
||||
break; |
||||
|
||||
case LED_ASSERTION: |
||||
phy_set_led(BOARD_LED_RED, false); |
||||
phy_set_led(BOARD_LED_BLUE, false); |
||||
break; |
||||
|
||||
case LED_PANIC: |
||||
phy_set_led(BOARD_LED_RED, false); |
||||
break; |
||||
|
||||
case LED_IDLE : /* IDLE */ |
||||
phy_set_led(BOARD_LED_RED, false); |
||||
break; |
||||
} |
||||
} |
||||
|
||||
#endif /* CONFIG_ARCH_LEDS */ |
@ -0,0 +1,129 @@
@@ -0,0 +1,129 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2018 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 manifest.c |
||||
* |
||||
* This module supplies the interface to the manifest of hardware that is |
||||
* optional and dependent on the HW REV and HW VER IDs |
||||
* |
||||
* The manifest allows the system to know whether a hardware option |
||||
* say for example the PX4IO is an no-pop option vs it is broken. |
||||
* |
||||
*/ |
||||
|
||||
/****************************************************************************
|
||||
* Included Files |
||||
****************************************************************************/ |
||||
|
||||
#include <nuttx/config.h> |
||||
#include <board_config.h> |
||||
|
||||
#include <stdbool.h> |
||||
|
||||
#include "systemlib/px4_macros.h" |
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions |
||||
****************************************************************************/ |
||||
|
||||
typedef struct { |
||||
uint32_t hw_ver_rev; /* the version and revision */ |
||||
const px4_hw_mft_item_t *mft; /* The first entry */ |
||||
uint32_t entries; /* the lenght of the list */ |
||||
} px4_hw_mft_list_entry_t; |
||||
|
||||
typedef px4_hw_mft_list_entry_t *px4_hw_mft_list_entry; |
||||
#define px4_hw_mft_list_uninitialized (px4_hw_mft_list_entry) -1 |
||||
|
||||
static const px4_hw_mft_item_t device_unsupported = {0, 0, 0}; |
||||
|
||||
// List of components on a specific board configuration
|
||||
// The index of those components is given by the enum (px4_hw_mft_item_id_t)
|
||||
// declared in board_common.h
|
||||
static const px4_hw_mft_item_t hw_mft_list_durandal[] = { |
||||
{ |
||||
.present = 1, |
||||
.mandatory = 1, |
||||
.connection = px4_hw_con_onboard, |
||||
}, |
||||
}; |
||||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = { |
||||
{0x0000, hw_mft_list_durandal, arraySize(hw_mft_list_durandal)}, |
||||
}; |
||||
|
||||
/************************************************************************************
|
||||
* Name: board_query_manifest |
||||
* |
||||
* Description: |
||||
* Optional returns manifest item. |
||||
* |
||||
* Input Parameters: |
||||
* manifest_id - the ID for the manifest item to retrieve |
||||
* |
||||
* Returned Value: |
||||
* 0 - item is not in manifest => assume legacy operations |
||||
* pointer to a manifest item |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id) |
||||
{ |
||||
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized; |
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) { |
||||
uint32_t ver_rev = board_get_hw_version() << 8; |
||||
ver_rev |= board_get_hw_revision(); |
||||
|
||||
for (unsigned i = 0; i < arraySize(mft_lists); i++) { |
||||
if (mft_lists[i].hw_ver_rev == ver_rev) { |
||||
boards_manifest = &mft_lists[i]; |
||||
break; |
||||
} |
||||
} |
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) { |
||||
syslog(LOG_ERR, "[boot] Board %4x is not supported!\n", ver_rev); |
||||
} |
||||
} |
||||
|
||||
px4_hw_mft_item rv = &device_unsupported; |
||||
|
||||
if (boards_manifest != px4_hw_mft_list_uninitialized && |
||||
id < boards_manifest->entries) { |
||||
rv = &boards_manifest->mft[id]; |
||||
} |
||||
|
||||
return rv; |
||||
} |
@ -0,0 +1,177 @@
@@ -0,0 +1,177 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. |
||||
* Author: Gregory Nutt <gnutt@nuttx.org> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name NuttX nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/****************************************************************************
|
||||
* Included Files |
||||
****************************************************************************/ |
||||
|
||||
#include <nuttx/config.h> |
||||
#include <board_config.h> |
||||
|
||||
#include <stdbool.h> |
||||
#include <stdio.h> |
||||
#include <debug.h> |
||||
#include <errno.h> |
||||
|
||||
#include <nuttx/sdio.h> |
||||
#include <nuttx/mmcsd.h> |
||||
|
||||
#include "chip.h" |
||||
#include "board_config.h" |
||||
#include "stm32_gpio.h" |
||||
#include "stm32_sdmmc.h" |
||||
|
||||
#ifdef CONFIG_MMCSD |
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions |
||||
****************************************************************************/ |
||||
|
||||
/* Card detections requires card support and a card detection GPIO */ |
||||
|
||||
#define HAVE_NCD 1 |
||||
#if !defined(GPIO_SDMMC1_NCD) |
||||
# undef HAVE_NCD |
||||
#endif |
||||
|
||||
/****************************************************************************
|
||||
* Private Data |
||||
****************************************************************************/ |
||||
|
||||
static FAR struct sdio_dev_s *sdio_dev; |
||||
#ifdef HAVE_NCD |
||||
static bool g_sd_inserted = 0xff; /* Impossible value */ |
||||
#endif |
||||
|
||||
/****************************************************************************
|
||||
* Private Functions |
||||
****************************************************************************/ |
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_ncd_interrupt |
||||
* |
||||
* Description: |
||||
* Card detect interrupt handler. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#ifdef HAVE_NCD |
||||
static int stm32_ncd_interrupt(int irq, FAR void *context) |
||||
{ |
||||
bool present; |
||||
|
||||
present = !stm32_gpioread(GPIO_SDMMC1_NCD); |
||||
|
||||
if (sdio_dev && present != g_sd_inserted) { |
||||
sdio_mediachange(sdio_dev, present); |
||||
g_sd_inserted = present; |
||||
} |
||||
|
||||
return OK; |
||||
} |
||||
#endif |
||||
|
||||
/****************************************************************************
|
||||
* Public Functions |
||||
****************************************************************************/ |
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_sdio_initialize |
||||
* |
||||
* Description: |
||||
* Initialize SDIO-based MMC/SD card support |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
int stm32_sdio_initialize(void) |
||||
{ |
||||
int ret; |
||||
|
||||
#ifdef HAVE_NCD |
||||
/* Card detect */ |
||||
|
||||
bool cd_status; |
||||
|
||||
/* Configure the card detect GPIO */ |
||||
|
||||
stm32_configgpio(GPIO_SDMMC1_NCD); |
||||
|
||||
/* Register an interrupt handler for the card detect pin */ |
||||
|
||||
stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); |
||||
#endif |
||||
|
||||
/* Mount the SDIO-based MMC/SD block driver */ |
||||
/* First, get an instance of the SDIO interface */ |
||||
|
||||
finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); |
||||
|
||||
sdio_dev = sdio_initialize(SDIO_SLOTNO); |
||||
|
||||
if (!sdio_dev) { |
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); |
||||
return -ENODEV; |
||||
} |
||||
|
||||
/* Now bind the SDIO interface to the MMC/SD driver */ |
||||
|
||||
finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); |
||||
|
||||
ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); |
||||
|
||||
if (ret != OK) { |
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); |
||||
return ret; |
||||
} |
||||
|
||||
finfo("Successfully bound SDIO to the MMC/SD driver\n"); |
||||
|
||||
#ifdef HAVE_NCD |
||||
/* Use SD card detect pin to check if a card is g_sd_inserted */ |
||||
|
||||
cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); |
||||
finfo("Card detect : %d\n", cd_status); |
||||
|
||||
sdio_mediachange(sdio_dev, cd_status); |
||||
#else |
||||
/* Assume that the SD card is inserted. What choice do we have? */ |
||||
|
||||
sdio_mediachange(sdio_dev, true); |
||||
#endif |
||||
|
||||
return OK; |
||||
} |
||||
|
||||
#endif /* CONFIG_MMCSD */ |
@ -0,0 +1,321 @@
@@ -0,0 +1,321 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 px4fmu_spi.c |
||||
* |
||||
* Board-specific SPI functions. |
||||
*/ |
||||
|
||||
/************************************************************************************
|
||||
* Included Files |
||||
************************************************************************************/ |
||||
|
||||
#include <board_config.h> |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include <debug.h> |
||||
#include <unistd.h> |
||||
|
||||
#include <nuttx/spi/spi.h> |
||||
#include <arch/board/board.h> |
||||
#include <systemlib/px4_macros.h> |
||||
|
||||
#include <up_arch.h> |
||||
#include <chip.h> |
||||
#include <stm32_gpio.h> |
||||
#include "board_config.h" |
||||
|
||||
/* Define CS GPIO array */ |
||||
static constexpr uint32_t spi1selects_gpio[] = PX4_SENSOR_BUS_CS_GPIO; |
||||
static constexpr uint32_t spi2selects_gpio[] = PX4_MEMORY_BUS_CS_GPIO; |
||||
static constexpr uint32_t spi4selects_gpio[] = PX4_BARO_BUS_CS_GPIO; |
||||
static constexpr uint32_t spi5selects_gpio[] = PX4_EXTERNAL1_BUS_CS_GPIO; |
||||
static constexpr uint32_t spi6selects_gpio[] = PX4_EXTERNAL2_BUS_CS_GPIO; |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spiinitialize |
||||
* |
||||
* Description: |
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void stm32_spiinitialize() |
||||
{ |
||||
#ifdef CONFIG_STM32H7_SPI1 |
||||
|
||||
for (auto gpio : spi1selects_gpio) { |
||||
px4_arch_configgpio(gpio); |
||||
} |
||||
|
||||
#endif // CONFIG_STM32H7_SPI1
|
||||
|
||||
|
||||
#if defined(CONFIG_STM32H7_SPI2) |
||||
|
||||
for (auto gpio : spi2selects_gpio) { |
||||
px4_arch_configgpio(gpio); |
||||
} |
||||
|
||||
#endif // CONFIG_STM32H7_SPI2
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32H7_SPI4 |
||||
|
||||
for (auto gpio : spi4selects_gpio) { |
||||
px4_arch_configgpio(gpio); |
||||
} |
||||
|
||||
#endif // CONFIG_STM32H7_SPI4
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32H7_SPI5 |
||||
|
||||
for (auto gpio : spi5selects_gpio) { |
||||
px4_arch_configgpio(gpio); |
||||
} |
||||
|
||||
#endif // CONFIG_STM32H7_SPI5
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32H7_SPI6 |
||||
|
||||
for (auto gpio : spi6selects_gpio) { |
||||
px4_arch_configgpio(gpio); |
||||
} |
||||
|
||||
#endif // CONFIG_STM32H7_SPI6
|
||||
} |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi1select and stm32_spi1status |
||||
* |
||||
* Description: |
||||
* Called by stm32 spi driver on bus 1. |
||||
* |
||||
************************************************************************************/ |
||||
#ifdef CONFIG_STM32H7_SPI1 |
||||
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) |
||||
{ |
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_SENSORS); |
||||
|
||||
// Making sure the other peripherals are not selected
|
||||
for (auto cs : spi1selects_gpio) { |
||||
stm32_gpiowrite(cs, 1); |
||||
} |
||||
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(spi1selects_gpio[PX4_SPI_DEV_ID(devid)], !selected); |
||||
} |
||||
|
||||
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) |
||||
{ |
||||
return SPI_STATUS_PRESENT; |
||||
} |
||||
#endif // CONFIG_STM32H7_SPI1
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi2select and stm32_spi2status |
||||
* |
||||
* Description: |
||||
* Called by stm32 spi driver on bus 2. |
||||
* |
||||
************************************************************************************/ |
||||
#if defined(CONFIG_STM32H7_SPI2) |
||||
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) |
||||
{ |
||||
if (devid == SPIDEV_FLASH(0)) { |
||||
devid = PX4_SPIDEV_MEMORY; |
||||
} |
||||
|
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_MEMORY); |
||||
|
||||
// Making sure the other peripherals are not selected
|
||||
for (auto cs : spi2selects_gpio) { |
||||
stm32_gpiowrite(cs, 1); |
||||
} |
||||
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(spi2selects_gpio[PX4_SPI_DEV_ID(devid)], !selected); |
||||
} |
||||
|
||||
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) |
||||
{ |
||||
return SPI_STATUS_PRESENT; |
||||
} |
||||
#endif // CONFIG_STM32H7_SPI2 && GPIO_SPI2_CS_FRAM
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi4select and stm32_spi4status |
||||
* |
||||
* Description: |
||||
* Called by stm32 spi driver on bus 4. |
||||
* |
||||
************************************************************************************/ |
||||
#ifdef CONFIG_STM32H7_SPI4 |
||||
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) |
||||
{ |
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_BARO); |
||||
|
||||
// Making sure the other peripherals are not selected
|
||||
for (auto cs : spi4selects_gpio) { |
||||
stm32_gpiowrite(cs, 1); |
||||
} |
||||
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(spi4selects_gpio[PX4_SPI_DEV_ID(devid)], !selected); |
||||
} |
||||
|
||||
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid) |
||||
{ |
||||
return SPI_STATUS_PRESENT; |
||||
} |
||||
#endif // CONFIG_STM32H7_SPI4
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi5select and stm32_spi5status |
||||
* |
||||
* Description: |
||||
* Called by stm32 spi driver on bus 5. |
||||
* |
||||
************************************************************************************/ |
||||
#ifdef CONFIG_STM32H7_SPI5 |
||||
__EXPORT void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) |
||||
{ |
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_EXTERNAL1); |
||||
|
||||
// Making sure the other peripherals are not selected
|
||||
for (auto cs : spi5selects_gpio) { |
||||
stm32_gpiowrite(cs, 1); |
||||
} |
||||
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(spi5selects_gpio[PX4_SPI_DEV_ID(devid)], !selected); |
||||
} |
||||
|
||||
__EXPORT uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid) |
||||
{ |
||||
return SPI_STATUS_PRESENT; |
||||
} |
||||
#endif // CONFIG_STM32H7_SPI5
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi6select and stm32_spi6status |
||||
* |
||||
* Description: |
||||
* Called by stm32 spi driver on bus 6. |
||||
* |
||||
************************************************************************************/ |
||||
#ifdef CONFIG_STM32H7_SPI6 |
||||
__EXPORT void stm32_spi6select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) |
||||
{ |
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_EXTERNAL2); |
||||
|
||||
// Making sure the other peripherals are not selected
|
||||
for (auto cs : spi6selects_gpio) { |
||||
stm32_gpiowrite(cs, 1); |
||||
} |
||||
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(spi6selects_gpio[PX4_SPI_DEV_ID(devid)], !selected); |
||||
} |
||||
|
||||
__EXPORT uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, uint32_t devid) |
||||
{ |
||||
return SPI_STATUS_PRESENT; |
||||
} |
||||
#endif // CONFIG_STM32H7_SPI6
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_spi_reset |
||||
* |
||||
* Description: |
||||
* |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void board_spi_reset(int ms) |
||||
{ |
||||
// disable SPI bus
|
||||
for (auto cs : spi1selects_gpio) { |
||||
stm32_configgpio(_PIN_OFF(cs)); |
||||
} |
||||
|
||||
stm32_configgpio(GPIO_SPI1_SCK_OFF); |
||||
stm32_configgpio(GPIO_SPI1_MISO_OFF); |
||||
stm32_configgpio(GPIO_SPI1_MOSI_OFF); |
||||
|
||||
|
||||
#if BOARD_USE_DRDY |
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY1_ICM20689); |
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY2_BMI088_GYRO); |
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY3_BMI088_ACC); |
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY4_ICM20602); |
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY5_BMI088_GYRO); |
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY6_BMI088_ACC); |
||||
#endif |
||||
/* set the sensor rail off */ |
||||
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0); |
||||
|
||||
/* wait for the sensor rail to reach GND */ |
||||
usleep(ms * 1000); |
||||
syslog(LOG_DEBUG, "reset done, %d ms\n", ms); |
||||
|
||||
/* re-enable power */ |
||||
|
||||
/* switch the sensor rail back on */ |
||||
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1); |
||||
|
||||
/* wait a bit before starting SPI, different times didn't influence results */ |
||||
usleep(100); |
||||
|
||||
/* reconfigure the SPI pins */ |
||||
for (auto cs : spi1selects_gpio) { |
||||
stm32_configgpio(cs); |
||||
} |
||||
|
||||
stm32_configgpio(GPIO_SPI1_SCK); |
||||
stm32_configgpio(GPIO_SPI1_MISO); |
||||
stm32_configgpio(GPIO_SPI1_MOSI); |
||||
|
||||
#if BOARD_USE_DRDY |
||||
stm32_configgpio(GPIO_SPI1_DRDY1_ICM20689); |
||||
stm32_configgpio(GPIO_SPI1_DRDY2_BMI055_GYRO); |
||||
stm32_configgpio(GPIO_SPI1_DRDY3_BMI055_ACC); |
||||
stm32_configgpio(GPIO_SPI1_DRDY4_ICM20602); |
||||
stm32_configgpio(GPIO_SPI1_DRDY5_BMI055_GYRO); |
||||
stm32_configgpio(GPIO_SPI1_DRDY6_BMI055_ACC); |
||||
#endif |
||||
} |
@ -0,0 +1,118 @@
@@ -0,0 +1,118 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 px4fmu_timer_config.c |
||||
* |
||||
* Configuration data for the stm32 pwm_servo, input capture and pwm input driver. |
||||
* |
||||
* Note that these arrays must always be fully-sized. |
||||
*/ |
||||
|
||||
#include <stdint.h> |
||||
|
||||
#include <chip.h> |
||||
#include <stm32_gpio.h> |
||||
#include <stm32_tim.h> |
||||
|
||||
#include <drivers/drv_pwm_output.h> |
||||
#include <px4_arch/io_timer.h> |
||||
|
||||
#include "board_config.h" |
||||
|
||||
__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = { |
||||
{ |
||||
.base = STM32_TIM1_BASE, |
||||
.clock_register = STM32_RCC_APB2ENR, |
||||
.clock_bit = RCC_APB2ENR_TIM1EN, |
||||
.clock_freq = STM32_APB2_TIM1_CLKIN, |
||||
.first_channel_index = 0, |
||||
.last_channel_index = 3, |
||||
.handler = io_timer_handler0, |
||||
.vectorno = STM32_IRQ_TIMCC, |
||||
|
||||
}, |
||||
{ |
||||
.base = STM32_TIM4_BASE, |
||||
.clock_register = STM32_RCC_APB1LENR, |
||||
.clock_bit = RCC_APB1LENR_TIM4EN, |
||||
.clock_freq = STM32_APB1_TIM4_CLKIN, |
||||
.first_channel_index = 4, |
||||
.last_channel_index = 4, |
||||
.handler = io_timer_handler1, |
||||
.vectorno = STM32_IRQ_TIM4, |
||||
}, |
||||
}; |
||||
|
||||
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { |
||||
{ |
||||
.gpio_out = GPIO_TIM1_CH4OUT, |
||||
.gpio_in = GPIO_TIM1_CH4IN, |
||||
.timer_index = 0, |
||||
.timer_channel = 4, |
||||
.ccr_offset = STM32_GTIM_CCR4_OFFSET, |
||||
.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF |
||||
}, |
||||
{ |
||||
.gpio_out = GPIO_TIM1_CH3OUT, |
||||
.gpio_in = GPIO_TIM1_CH3IN, |
||||
.timer_index = 0, |
||||
.timer_channel = 3, |
||||
.ccr_offset = STM32_GTIM_CCR3_OFFSET, |
||||
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF |
||||
}, |
||||
{ |
||||
.gpio_out = GPIO_TIM1_CH2OUT, |
||||
.gpio_in = GPIO_TIM1_CH2IN, |
||||
.timer_index = 0, |
||||
.timer_channel = 2, |
||||
.ccr_offset = STM32_GTIM_CCR2_OFFSET, |
||||
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF |
||||
}, |
||||
{ |
||||
.gpio_out = GPIO_TIM1_CH1OUT, |
||||
.gpio_in = GPIO_TIM1_CH1IN, |
||||
.timer_index = 0, |
||||
.timer_channel = 1, |
||||
.ccr_offset = STM32_GTIM_CCR1_OFFSET, |
||||
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF |
||||
}, |
||||
{ |
||||
.gpio_out = GPIO_TIM4_CH2OUT, |
||||
.gpio_in = GPIO_TIM4_CH2IN, |
||||
.timer_index = 1, |
||||
.timer_channel = 2, |
||||
.ccr_offset = STM32_GTIM_CCR2_OFFSET, |
||||
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF |
||||
}, |
||||
}; |
@ -0,0 +1,105 @@
@@ -0,0 +1,105 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2016 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file px4fmu_usb.c |
||||
* |
||||
* Board-specific USB functions. |
||||
*/ |
||||
|
||||
/************************************************************************************
|
||||
* Included Files |
||||
************************************************************************************/ |
||||
|
||||
#include <px4_platform_common/px4_config.h> |
||||
|
||||
#include <sys/types.h> |
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include <debug.h> |
||||
|
||||
#include <nuttx/usb/usbdev.h> |
||||
#include <nuttx/usb/usbdev_trace.h> |
||||
|
||||
#include <up_arch.h> |
||||
#include <chip.h> |
||||
#include <stm32_gpio.h> |
||||
#include <stm32_otg.h> |
||||
#include "board_config.h" |
||||
|
||||
/************************************************************************************
|
||||
* Definitions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Private Functions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Public Functions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbinitialize |
||||
* |
||||
* Description: |
||||
* Called to setup USB-related GPIO pins for the PX4FMU board. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void stm32_usbinitialize(void) |
||||
{ |
||||
/* The OTG FS has an internal soft pull-up */ |
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ |
||||
|
||||
#ifdef CONFIG_STM32H7_OTGFS |
||||
stm32_configgpio(GPIO_OTGFS_VBUS); |
||||
#endif |
||||
} |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend |
||||
* |
||||
* Description: |
||||
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is |
||||
* used. This function is called whenever the USB enters or leaves suspend mode. |
||||
* This is an opportunity for the board logic to shutdown clocks, power, etc. |
||||
* while the USB is suspended. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) |
||||
{ |
||||
uinfo("resume: %d\n", resume); |
||||
} |
Loading…
Reference in new issue