fmuv5x board support

This commit is contained in:
David Sidrane 2019-05-28 15:18:38 -07:00 committed by Daniel Agar
parent 6e9f706b12
commit 31dfaee76a
26 changed files with 4606 additions and 0 deletions

View File

@ -36,6 +36,7 @@ pipeline {
"px4_fmu-v4_default",
"px4_fmu-v4pro_default",
"px4_fmu-v5_default", "px4_fmu-v5_fixedwing", "px4_fmu-v5_multicopter", "px4_fmu-v5_rover", "px4_fmu-v5_rtps", "px4_fmu-v5_stackcheck",
"px4_fmu-v5x_default", "px4_fmu-v5x_fixedwing", "px4_fmu-v5x_multicopter", "px4_fmu-v5x_rover", "px4_fmu-v5x_rtps", "px4_fmu-v5x_stackcheck",
"intel_aerofc-v1_default", "auav_x21_default", "av_x-v1_default", "bitcraze_crazyflie_default", "airmind_mindpx-v2_default",
"nxp_fmuk66-v3_default", "omnibus_f4sd_default"],
image: docker_images.nuttx,

View File

@ -248,6 +248,7 @@ px4fmu_firmware: \
check_px4_fmu-v4_default \
check_px4_fmu-v4pro_default \
check_px4_fmu-v5_default \
check_px4_fmu-v5x_default \
sizes
misc_qgc_extra_firmware: \

View File

@ -0,0 +1,130 @@
px4_add_board(
PLATFORM nuttx
VENDOR px4
MODEL fmu-v5x
LABEL default
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
IO px4_io-v2_default
TESTING
UAVCAN_INTERFACES 2
SERIAL_PORTS
GPS1:/dev/ttyS1
TEL1:/dev/ttyS6
TEL2:/dev/ttyS4
TEL3:/dev/ttyS2
GPS2:/dev/ttyS0
DRIVERS
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
gps
#heater
imu/adis16448
imu/adis16497
#imu # all available imu drivers
# TBD imu/bmi088 - needs bus selection
# TBD imu/ism330dlc - needs bus selection
imu/mpu6000
irlock
lights/blinkm
lights/oreoled
lights/pca8574
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
pwm_out_sim
px4fmu
px4io
rc_input
roboclaw
stm32
stm32/adc
stm32/armv7-m_dcache
stm32/tone_alarm
tap_esc
telemetry # all available telemetry drivers
test_ppm
tone_alarm
uavcan
MODULES
attitude_estimator_q
camera_feedback
commander
dataman
ekf2
events
fw_att_control
fw_pos_control_l1
gnd_att_control
gnd_pos_control
land_detector
landing_target_estimator
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_pos_control
navigator
sensors
sih
vmount
vtol_att_control
wind_estimator
SYSTEMCMDS
bl_update
config
dmesg
dumpfile
esc_calib
hardfault_log
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
EXAMPLES
bottle_drop # OBC challenge
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
hello
hwtest # Hardware test
#matlab_csv_serial
position_estimator_inav
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
segway
uuv_example_app
)

View File

@ -0,0 +1,13 @@
{
"board_id": 51,
"magic": "PX4FWv1",
"description": "Firmware for the PX4FMUv5X board",
"image": "",
"build_time": 0,
"summary": "PX4FMUv5X",
"version": "0.1",
"image_size": 0,
"image_maxsize": 2064384,
"git_identity": "",
"board_revision": 0
}

View File

@ -0,0 +1,99 @@
px4_add_board(
PLATFORM nuttx
VENDOR px4
MODEL fmu-v5x
LABEL fixedwing
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
IO px4_io-v2_default
UAVCAN_INTERFACES 2
SERIAL_PORTS
GPS1:/dev/ttyS1
TEL1:/dev/ttyS6
TEL2:/dev/ttyS4
TEL3:/dev/ttyS2
GPS2:/dev/ttyS0
DRIVERS
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
gps
#heater
imu/adis16448
imu/adis16497
#imu # all available imu drivers
# TBD imu/bmi088 - needs bus selection
# TBD imu/ism330dlc - needs bus selection
imu/mpu6000
irlock
lights/blinkm
lights/oreoled
lights/pca8574
lights/rgbled
lights/rgbled_ncp5623c
magnetometer # all available magnetometer drivers
optical_flow # all available optical flow drivers
power_monitor/ina226
pwm_input
pwm_out_sim
px4fmu
px4io
rc_input
stm32
stm32/adc
stm32/armv7-m_dcache
stm32/tone_alarm
telemetry # all available telemetry drivers
tone_alarm
uavcan
MODULES
camera_feedback
commander
dataman
ekf2
events
fw_att_control
fw_pos_control_l1
land_detector
load_mon
logger
mavlink
navigator
sensors
vmount
wind_estimator
SYSTEMCMDS
bl_update
config
dmesg
dumpfile
esc_calib
hardfault_log
led_control
mixer
motor_ramp
motor_test
mtd
nshterm
param
perf
pwm
reboot
reflect
sd_bench
shutdown
top
topic_listener
tune_control
usb_connected
ver
)

View File

@ -0,0 +1,12 @@
#!/bin/sh
#
# PX4 FMUv5X specific board defaults
#------------------------------------------------------------------------------
if [ $AUTOCNF = yes ]
then
fi
set LOGGER_BUF 64

View File

@ -0,0 +1,31 @@
#!/bin/sh
#
# PX4 FMUv5X specific board sensors init
#------------------------------------------------------------------------------
# Internal SPI bus ICM-20602
mpu6000 -R 8 -s -T 20602 start
# Internal SPI bus ISM300DLC
ism330dlc 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
# Possible internal compass
bmm150 -C start
# Possible internal Barro
bmp388 -C start
# Possible pmw3901 optical flow sensor
pmw3901 start

View File

@ -0,0 +1,105 @@
px4_add_board(
PLATFORM nuttx
VENDOR px4
MODEL fmu-v5x
LABEL multicopter
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
IO px4_io-v2_default
TESTING
UAVCAN_INTERFACES 2
SERIAL_PORTS
GPS1:/dev/ttyS1
TEL1:/dev/ttyS6
TEL2:/dev/ttyS4
TEL3:/dev/ttyS2
GPS2:/dev/ttyS0
DRIVERS
barometer # all available barometer drivers
batt_smbus
camera_capture
camera_trigger
distance_sensor # all available distance sensor drivers
gps
#heater
imu/adis16448
imu/adis16497
#imu # all available imu drivers
# TBD imu/bmi088 - needs bus selection
# TBD imu/ism330dlc - needs bus selection
imu/mpu6000
irlock
lights/blinkm
lights/oreoled
lights/pca8574
lights/rgbled
lights/rgbled_ncp5623c
magnetometer # all available magnetometer drivers
optical_flow # all available optical flow drivers
power_monitor/ina226
pwm_input
pwm_out_sim
px4fmu
px4io
rc_input
roboclaw
stm32
stm32/adc
stm32/armv7-m_dcache
stm32/tone_alarm
tap_esc
telemetry # all available telemetry drivers
tone_alarm
uavcan
MODULES
attitude_estimator_q
camera_feedback
commander
dataman
ekf2
events
land_detector
landing_target_estimator
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_pos_control
navigator
sensors
sih
vmount
wind_estimator
SYSTEMCMDS
bl_update
config
dmesg
dumpfile
esc_calib
hardfault_log
led_control
mixer
motor_ramp
motor_test
mtd
nshterm
param
perf
pwm
reboot
reflect
sd_bench
shutdown
top
topic_listener
tune_control
usb_connected
ver
)

View File

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

View File

@ -0,0 +1,543 @@
/************************************************************************************
* nuttx-configs/px4_fmu-v5x/include/board.h
*
* Copyright (C) 2016-2019 Gregory Nutt. All rights reserved.
* Authors: David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __NUTTX_CONFIG_PX4_FMU_V5X_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_PX4_FMU_V5X_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 px4_fmu-v5 board provides the following clock sources:
*
* X301: 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 0
/* Main PLL Configuration.
*
* PLL source is HSE = 16,000,000
*
* PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
* Subject to:
*
* 2 <= PLLM <= 63
* 192 <= PLLN <= 432
* 192 MHz <= PLL_VCO <= 432MHz
*
* SYSCLK = PLL_VCO / PLLP
* Subject to
*
* PLLP = {2, 4, 6, 8}
* SYSCLK <= 216 MHz
*
* USB OTG FS, SDMMC and RNG Clock = PLL_VCO / PLLQ
* Subject to
* The USB OTG FS requires a 48 MHz clock to work correctly. The SDMMC
* and the random number generator need a frequency lower than or equal
* to 48 MHz to work correctly.
*
* 2 <= PLLQ <= 15
*/
/* Highest SYSCLK with USB OTG FS clock = 48 MHz
*
* PLL_VCO = (16,000,000 / 8) * 216 = 432 MHz
* SYSCLK = 432 MHz / 2 = 216 MHz
* USB OTG FS, SDMMC and RNG Clock = 432 MHz / 9 = 48 MHz
*/
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(216)
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(9)
#define STM32_VCO_FREQUENCY ((STM32_HSE_FREQUENCY / 8) * 216)
#define STM32_SYSCLK_FREQUENCY (STM32_VCO_FREQUENCY / 2)
#define STM32_OTGFS_FREQUENCY (STM32_VCO_FREQUENCY / 9)
/* Configure factors for PLLSAI clock */
#define CONFIG_STM32F7_PLLSAI 1
#define STM32_RCC_PLLSAICFGR_PLLSAIN RCC_PLLSAICFGR_PLLSAIN(192)
#define STM32_RCC_PLLSAICFGR_PLLSAIP RCC_PLLSAICFGR_PLLSAIP(8)
#define STM32_RCC_PLLSAICFGR_PLLSAIQ RCC_PLLSAICFGR_PLLSAIQ(4)
#define STM32_RCC_PLLSAICFGR_PLLSAIR RCC_PLLSAICFGR_PLLSAIR(2)
/* Configure Dedicated Clock Configuration Register */
#define STM32_RCC_DCKCFGR1_PLLI2SDIVQ RCC_DCKCFGR1_PLLI2SDIVQ(1)
#define STM32_RCC_DCKCFGR1_PLLSAIDIVQ RCC_DCKCFGR1_PLLSAIDIVQ(1)
#define STM32_RCC_DCKCFGR1_PLLSAIDIVR RCC_DCKCFGR1_PLLSAIDIVR(0)
#define STM32_RCC_DCKCFGR1_SAI1SRC RCC_DCKCFGR1_SAI1SEL(0)
#define STM32_RCC_DCKCFGR1_SAI2SRC RCC_DCKCFGR1_SAI2SEL(0)
#define STM32_RCC_DCKCFGR1_TIMPRESRC 0
#define STM32_RCC_DCKCFGR1_DFSDM1SRC 0
#define STM32_RCC_DCKCFGR1_ADFSDM1SRC 0
/* Configure factors for PLLI2S clock */
#define CONFIG_STM32F7_PLLI2S 1
#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192)
#define STM32_RCC_PLLI2SCFGR_PLLI2SP RCC_PLLI2SCFGR_PLLI2SP(2)
#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2)
#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
/* Configure Dedicated Clock Configuration Register 2 */
#define STM32_RCC_DCKCFGR2_USART1SRC RCC_DCKCFGR2_USART1SEL_APB
#define STM32_RCC_DCKCFGR2_USART2SRC RCC_DCKCFGR2_USART2SEL_APB
#define STM32_RCC_DCKCFGR2_UART4SRC RCC_DCKCFGR2_UART4SEL_APB
#define STM32_RCC_DCKCFGR2_UART5SRC RCC_DCKCFGR2_UART5SEL_APB
#define STM32_RCC_DCKCFGR2_USART6SRC RCC_DCKCFGR2_USART6SEL_APB
#define STM32_RCC_DCKCFGR2_UART7SRC RCC_DCKCFGR2_UART7SEL_APB
#define STM32_RCC_DCKCFGR2_UART8SRC RCC_DCKCFGR2_UART8SEL_APB
#define STM32_RCC_DCKCFGR2_I2C1SRC RCC_DCKCFGR2_I2C1SEL_HSI
#define STM32_RCC_DCKCFGR2_I2C2SRC RCC_DCKCFGR2_I2C2SEL_HSI
#define STM32_RCC_DCKCFGR2_I2C3SRC RCC_DCKCFGR2_I2C3SEL_HSI
#define STM32_RCC_DCKCFGR2_I2C4SRC RCC_DCKCFGR2_I2C4SEL_HSI
#define STM32_RCC_DCKCFGR2_LPTIM1SRC RCC_DCKCFGR2_LPTIM1SEL_APB
#define STM32_RCC_DCKCFGR2_CECSRC RCC_DCKCFGR2_CECSEL_HSI
#define STM32_RCC_DCKCFGR2_CK48MSRC RCC_DCKCFGR2_CK48MSEL_PLL
#define STM32_RCC_DCKCFGR2_SDMMCSRC RCC_DCKCFGR2_SDMMCSEL_48MHZ
#define STM32_RCC_DCKCFGR2_SDMMC2SRC RCC_DCKCFGR2_SDMMC2SEL_48MHZ
#define STM32_RCC_DCKCFGR2_DSISRC RCC_DCKCFGR2_DSISEL_PHY
/* Several prescalers allow the configuration of the two AHB buses, the
* high-speed APB (APB2) and the low-speed APB (APB1) domains. The maximum
* frequency of the two AHB buses is 216 MHz while the maximum frequency of
* the high-speed APB domains is 108 MHz. The maximum allowed frequency of
* the low-speed APB domain is 54 MHz.
*/
/* AHB clock (HCLK) is SYSCLK (216 MHz) */
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
/* APB1 clock (PCLK1) is HCLK/4 (54 MHz) */
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
/* Timers driven from APB1 will be twice PCLK1 */
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
/* APB2 clock (PCLK2) is HCLK/2 (108MHz) */
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* Timers driven from APB2 will be twice PCLK2 */
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
/* SDMMC dividers. Note that slower clocking is required when DMA is disabled
* in order to avoid RX overrun/TX underrun errors due to delayed responses
* to service FIFOs in interrupt driven mode. These values have not been
* tuned!!!
*
* SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(118+2)=400 KHz
*/
/* Use the Falling edge of the SDIO_CLK clock to change the edge the
* data and commands are change on
*/
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
#define STM32_SDMMC_INIT_CLKDIV (118 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz
* DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz
*/
#ifdef CONFIG_STM32F7_SDMMC_DMA
# define STM32_SDMMC_MMCXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_MMCXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz
* DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz
*/
//TODO #warning "Check Freq for 24mHz"
#ifdef CONFIG_STM32F7_SDMMC_DMA
# define STM32_SDMMC_SDXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_SDXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
/* DMA Channel/Stream Selections *****************************************************/
/* Stream selections are arbitrary for now but might become important in the future
* if we set aside more DMA channels/streams.
*
* SDMMC RX and TX DMA is on DMA2
*
* SDMMC2 DMA
* DMAMAP_SDMMC2_1 = Channel 11, Stream 0
* DMAMAP_SDMMC2_2 = Channel 11, Stream 5 <- Free for other devices
*/
#define DMAMAP_SDMMC2 DMAMAP_SDMMC1_1
/* FLASH wait states
*
* --------- ---------- -----------
* VDD MAX SYSCLK WAIT STATES
* --------- ---------- -----------
* 1.7-2.1 V 180 MHz 8
* 2.1-2.4 V 216 MHz 9
* 2.4-2.7 V 216 MHz 8
* 2.7-3.6 V 216 MHz 7
* --------- ---------- -----------
*/
#define BOARD_FLASH_WAITSTATES 7
/* LED definitions ******************************************************************/
/* The px4_fmu-v5 board has numerous LEDs but only 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 /* PB15 */
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB14 */
#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
#define GPIO_USART2_CTS GPIO_USART2_CTS_2 /* PD3 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PH14 */
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PH13 */
#define GPIO_UART5_RX GPIO_UART5_RX_1 /* PD2 */
#define GPIO_UART5_TX GPIO_UART5_TX_4 /* PB9 */
#define GPIO_UART5_RTS GPIO_UART5_RTS_1 /* PC8 */
#define GPIO_UART5_CTS GPIO_UART5_CTS_1 /* PC9 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC 7 */
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
#define GPIO_UART7_RX GPIO_UART7_RX_2 /* PF6 */
#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */
#define GPIO_UART7_RTS GPIO_UART7_RTS_1 /* PE9 */
#define GPIO_UART7_CTS GPIO_UART7_CTS_1 /* PE10 */
/* UART8: has no remap
*
* GPIO_UART8_RX PE0
* GPIO_UART8_TX PE1
*/
/* U[x]ART DMA configurations */
// #define DMAMAP_UART5_RX - DMA1, STREAM 0, Chan 4 - not remapable
// #define DMAMAP_UART5_TX - DMA1, STREAM 7, Chan 4 - not remapable
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_1 /* DMA2, STREAM 1, Chan 5 */
#define DMAMAP_USART6_TX DMAMAP_USART6_TX_2 /* DMA2, STREAM 7, Chan 5 */
// #define DMAMAP_UART7_RX - DMA1, STREAM 3, Chan 5 - not remapable
// #define DMAMAP_UART8_RX - DMA1, STREAM 6, Chan 5 - not remapable
/* CAN
*
* CAN1 is routed to transceiver.
* CAN2 is routed to transceiver.
*/
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
#define GPIO_CAN2_TX GPIO_CAN2_TX_2 /* PB6 */
/* SPI
* SPI1 is sensors1
* SPI2 is sensors2
* SPI3 is sensors3
* SPI4 is MAG
* SPI5 is FRAM
* SPI6 is EXTERNAL1
*
*/
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_2 /* PB4 */
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /* PA5 */
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PI3 */
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_5 /* PI1 */
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1 /* PB2 */
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2 /* PC10 */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE13 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE6 */
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_2 /* PE12 */
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF11 */
#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1 /* PF7 */
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */
#define GPIO_SPI6_SCK GPIO_SPI6_SCK_3 /* PB3 */
/* I2C
*
* The optional _GPIO configurations allow the I2C driver to manually
* reset the bus to clear stuck slaves. They match the pin configuration,
* but are normally-high GPIOs.
*
*/
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_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)
/* SDMMC2
*
* VDD 3.3
* GND
* SDMMC2_CK PD6
* SDMMC2_CMD PD7
* SDMMC2_D0 PG9
* SDMMC2_D1 PG10
* SDMMC2_D2 PG11
* SDMMC2_D3 PG12
*/
#define GPIO_SDMMC2_D0 GPIO_SDMMC2_D0_2
#define GPIO_SDMMC2_D1 GPIO_SDMMC2_D1_2
#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_2
#define GPIO_SDMMC2_D3 GPIO_SDMMC2_D3_2
/* 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_PORTA|GPIO_PIN8) /* PA8 AUX4 */
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */
# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */
# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 CAP1 */
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
#else
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)
#endif
/************************************************************************************
* 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_PX4_FMU_V5X_INCLUDE_BOARD_H */

View File

@ -0,0 +1,248 @@
# 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_DIR="../nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP_STM32F765II=y
CONFIG_ARCH_CHIP_STM32F7=y
CONFIG_ARCH_INTERRUPTSTACK=750
CONFIG_ARCH_MATH_H=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_FINALINIT=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=22114
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTID=0x0033
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v5X.x"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3185
CONFIG_CDCACM_VENDORSTR="Auterion"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_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_RAMTRON=y
CONFIG_NFILE_DESCRIPTORS=54
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_PSSTACKUSAGE=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=1800
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1800
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_STM32F7_ADC1=y
CONFIG_STM32F7_BBSRAM=y
CONFIG_STM32F7_BBSRAM_FILES=5
CONFIG_STM32F7_BKPSRAM=y
CONFIG_STM32F7_DMA1=y
CONFIG_STM32F7_DMA2=y
CONFIG_STM32F7_DMACAPABLE=y
CONFIG_STM32F7_FLOWCONTROL_BROKEN=y
CONFIG_STM32F7_I2C1=y
CONFIG_STM32F7_I2C2=y
CONFIG_STM32F7_I2C3=y
CONFIG_STM32F7_I2C4=y
CONFIG_STM32F7_I2C_DYNTIMEO=y
CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32F7_OTGFS=y
CONFIG_STM32F7_PWR=y
CONFIG_STM32F7_RTC=y
CONFIG_STM32F7_RTC_HSECLOCK=y
CONFIG_STM32F7_RTC_MAGIC_REG=1
CONFIG_STM32F7_SAVE_CRASHDUMP=y
CONFIG_STM32F7_SDMMC2=y
CONFIG_STM32F7_SDMMC_DMA=y
CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32F7_SPI1=y
CONFIG_STM32F7_SPI2=y
CONFIG_STM32F7_SPI3=y
CONFIG_STM32F7_SPI4=y
CONFIG_STM32F7_SPI5=y
CONFIG_STM32F7_SPI6=y
CONFIG_STM32F7_TIM10=y
CONFIG_STM32F7_TIM11=y
CONFIG_STM32F7_TIM3=y
CONFIG_STM32F7_TIM9=y
CONFIG_STM32F7_UART4=y
CONFIG_STM32F7_UART5=y
CONFIG_STM32F7_UART7=y
CONFIG_STM32F7_UART8=y
CONFIG_STM32F7_USART1=y
CONFIG_STM32F7_USART2=y
CONFIG_STM32F7_USART3=y
CONFIG_STM32F7_USART6=y
CONFIG_STM32F7_USART_BREAKS=y
CONFIG_STM32F7_USART_SINGLEWIRE=y
CONFIG_STM32F7_WWDG=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TIME_EXTENDED=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART5_IFLOWCONTROL=y
CONFIG_UART5_OFLOWCONTROL=y
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_RXDMA=y
CONFIG_UART5_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_IFLOWCONTROL=y
CONFIG_UART7_OFLOWCONTROL=y
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_TXBUFSIZE=3000
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_UART8_RXDMA=y
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART3_SERIAL_CONSOLE=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=180
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
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"

View File

@ -0,0 +1,183 @@
/****************************************************************************
* scripts/script.ld
*
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The STM32F765IIT6 has 2048 KiB of main FLASH memory. This FLASH memory
* can be accessed from either the AXIM interface at address 0x0800:0000 or
* from the ITCM interface at address 0x0020:0000.
*
* Additional information, including the option bytes, is available at at
* FLASH at address 0x1ff0:0000 (AXIM) or 0x0010:0000 (ITCM).
*
* In the STM32F765IIT6, two different boot spaces can be selected through
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
* BOOT_ADD1 option bytes:
*
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
* ST programmed value: Flash on ITCM at 0x0020:0000
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
* ST programmed value: System bootloader at 0x0010:0000
*
* NuttX does not modify these option byes. On the unmodified NUCLEO-144
* board, the BOOT0 pin is at ground so by default, the STM32F765IIT6 will
* boot from address 0x0020:0000 in ITCM FLASH.
*
* The STM32F765IIT6 also has 512 KiB of data SRAM (in addition to ITCM SRAM).
* SRAM is split up into three blocks:
*
* 1) 128 KiB of DTCM SRM beginning at address 0x2000:0000
* 2) 368 KiB of SRAM1 beginning at address 0x2002:0000
* 3) 16 KiB of SRAM2 beginning at address 0x2007:c000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*
* Bootloader reserves the first 32K bank (2 Mbytes Flash memory single bank)
* organization (256 bits read width)
*/
MEMORY
{
itcm (rwx) : ORIGIN = 0x00208000, LENGTH = 2016K
flash (rx) : ORIGIN = 0x08008000, LENGTH = 2016K
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
sram1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K
sram2 (rwx) : ORIGIN = 0x2007c000, LENGTH = 16K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
EXTERN(_bootdelay_signature)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
/*
* This is a hack to make the newlib libm __errno() call
* use the NuttX get_errno_ptr() function.
*/
__errno = get_errno_ptr;
} > flash
/*
* 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(.);
} > sram1 AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram1
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -0,0 +1,249 @@
# 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_DIR="../nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP_STM32F765II=y
CONFIG_ARCH_CHIP_STM32F7=y
CONFIG_ARCH_INTERRUPTSTACK=750
CONFIG_ARCH_MATH_H=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_STACKCHECK=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_FINALINIT=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=22114
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTID=0x0033
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v5X.x"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3185
CONFIG_CDCACM_VENDORSTR="Auterion"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_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_RAMTRON=y
CONFIG_NFILE_DESCRIPTORS=54
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_PSSTACKUSAGE=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=1800
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1800
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_STM32F7_ADC1=y
CONFIG_STM32F7_BBSRAM=y
CONFIG_STM32F7_BBSRAM_FILES=5
CONFIG_STM32F7_BKPSRAM=y
CONFIG_STM32F7_DMA1=y
CONFIG_STM32F7_DMA2=y
CONFIG_STM32F7_DMACAPABLE=y
CONFIG_STM32F7_FLOWCONTROL_BROKEN=y
CONFIG_STM32F7_I2C1=y
CONFIG_STM32F7_I2C2=y
CONFIG_STM32F7_I2C3=y
CONFIG_STM32F7_I2C4=y
CONFIG_STM32F7_I2C_DYNTIMEO=y
CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32F7_OTGFS=y
CONFIG_STM32F7_PWR=y
CONFIG_STM32F7_RTC=y
CONFIG_STM32F7_RTC_HSECLOCK=y
CONFIG_STM32F7_RTC_MAGIC_REG=1
CONFIG_STM32F7_SAVE_CRASHDUMP=y
CONFIG_STM32F7_SDMMC2=y
CONFIG_STM32F7_SDMMC_DMA=y
CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32F7_SPI1=y
CONFIG_STM32F7_SPI2=y
CONFIG_STM32F7_SPI3=y
CONFIG_STM32F7_SPI4=y
CONFIG_STM32F7_SPI5=y
CONFIG_STM32F7_SPI6=y
CONFIG_STM32F7_TIM10=y
CONFIG_STM32F7_TIM11=y
CONFIG_STM32F7_TIM3=y
CONFIG_STM32F7_TIM9=y
CONFIG_STM32F7_UART4=y
CONFIG_STM32F7_UART5=y
CONFIG_STM32F7_UART7=y
CONFIG_STM32F7_UART8=y
CONFIG_STM32F7_USART1=y
CONFIG_STM32F7_USART2=y
CONFIG_STM32F7_USART3=y
CONFIG_STM32F7_USART6=y
CONFIG_STM32F7_USART_BREAKS=y
CONFIG_STM32F7_USART_SINGLEWIRE=y
CONFIG_STM32F7_WWDG=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TIME_EXTENDED=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART5_IFLOWCONTROL=y
CONFIG_UART5_OFLOWCONTROL=y
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_RXDMA=y
CONFIG_UART5_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_IFLOWCONTROL=y
CONFIG_UART7_OFLOWCONTROL=y
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_TXBUFSIZE=3000
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_UART8_RXDMA=y
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART3_SERIAL_CONSOLE=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=180
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
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"

View File

@ -0,0 +1,102 @@
px4_add_board(
PLATFORM nuttx
VENDOR px4
MODEL fmu-v5x
LABEL rover
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
IO px4_io-v2_default
UAVCAN_INTERFACES 2
SERIAL_PORTS
GPS1:/dev/ttyS1
TEL1:/dev/ttyS6
TEL2:/dev/ttyS4
TEL3:/dev/ttyS2
GPS2:/dev/ttyS0
DRIVERS
barometer # all available barometer drivers
batt_smbus
camera_capture
camera_trigger
distance_sensor # all available distance sensor drivers
gps
#heater
imu/adis16448
imu/adis16497
#imu # all available imu drivers
# TBD imu/bmi088 - needs bus selection
# TBD imu/ism330dlc - needs bus selection
imu/mpu6000
irlock
lights/blinkm
lights/oreoled
lights/pca8574
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
pwm_out_sim
px4fmu
px4io
rc_input
roboclaw
stm32
stm32/adc
stm32/armv7-m_dcache
stm32/tone_alarm
telemetry # all available telemetry drivers
tone_alarm
uavcan
MODULES
camera_feedback
commander
dataman
ekf2
events
gnd_att_control
gnd_pos_control
land_detector
load_mon
logger
mavlink
navigator
sensors
vmount
SYSTEMCMDS
bl_update
config
dmesg
dumpfile
esc_calib
hardfault_log
led_control
mixer
motor_ramp
motor_test
mtd
nshterm
param
perf
pwm
reboot
reflect
sd_bench
shutdown
top
topic_listener
tune_control
usb_connected
ver
)

View File

@ -0,0 +1,131 @@
px4_add_board(
PLATFORM nuttx
VENDOR px4
MODEL fmu-v5x
LABEL rtps
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
IO px4_io-v2_default
TESTING
UAVCAN_INTERFACES 2
SERIAL_PORTS
GPS1:/dev/ttyS1
TEL1:/dev/ttyS6
TEL2:/dev/ttyS4
TEL3:/dev/ttyS2
GPS2:/dev/ttyS0
DRIVERS
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
gps
#heater
imu/adis16448
imu/adis16497
#imu # all available imu drivers
# TBD imu/bmi088 - needs bus selection
# TBD imu/ism330dlc - needs bus selection
imu/mpu6000
irlock
lights/blinkm
lights/oreoled
lights/pca8574
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
pwm_out_sim
px4fmu
px4io
rc_input
roboclaw
stm32
stm32/adc
stm32/armv7-m_dcache
stm32/tone_alarm
tap_esc
telemetry # all available telemetry drivers
test_ppm
tone_alarm
uavcan
MODULES
attitude_estimator_q
camera_feedback
commander
dataman
ekf2
events
fw_att_control
fw_pos_control_l1
gnd_att_control
gnd_pos_control
land_detector
landing_target_estimator
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_pos_control
micrortps_bridge
navigator
sensors
sih
vmount
vtol_att_control
wind_estimator
SYSTEMCMDS
bl_update
config
dmesg
dumpfile
esc_calib
hardfault_log
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
EXAMPLES
bottle_drop # OBC challenge
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
hello
hwtest # Hardware test
#matlab_csv_serial
position_estimator_inav
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
segway
uuv_example_app
)

View File

@ -0,0 +1,51 @@
############################################################################
#
# 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
)
target_link_libraries(drivers_board
PRIVATE
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio
px4_layer
)

View File

@ -0,0 +1,735 @@
/****************************************************************************
*
* 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 board_config.h
*
* PX4FMU-v5 internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <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/ttyS5"
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
#define PX4IO_SERIAL_BASE STM32_USART6_BASE
#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX
#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR
#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN
#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
/* Configuration ************************************************************************************/
#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks
#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid
#define BOARD_HAS_NBAT_V 2d // 2 Digital Voltage
#define BOARD_HAS_NBAT_I 2d // 2 Digital Current
/* PX4FMU GPIOs ***********************************************************************************/
/* Trace Clock and D0-D3 are available on the debug connector and adjacent pads
*
* TRACECLK PE2 - Dedicated - Debug Connector Pin 7
* TRACED0 PE3 - nLED_RED - Debug Connector Pin 8
* TRACED1 PE4 - nLED_GREEN - Test Point next to Debug Connector
* TRACED2 PE5 - nLED_BLUE - Test Point next to Debug Connector
* TRACED3 PC12 - nARMED - Test Point next to Debug Connector
*/
#undef TRACE_PINS
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */
#if !defined(TRACE_PINS)
# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5)
# define BOARD_HAS_CONTROL_STATUS_LEDS 1
# define BOARD_OVERLOAD_LED LED_RED
# define BOARD_ARMED_STATE_LED LED_BLUE
#endif
/* SPI
*
* SPI1 is sensors1
* ICM-20602
* CS PI9
* DRDY PF2
*
* SPI2 is sensors2
* ISM330
* CS PH5
* DRDY PH12
*
* SPI3 is sensors3
* BMI088
* CS ACCL PI4
* CS GYRO PI8
* DRDY ACCL PI6
* DRDY GYRO PI7
*
* SPI4 is MAG
* BMM150
* CS PH15
* DRDY PF3
*
* SPI5 is FRAM
* FM25V02A
* CS PG7
*
* SPI6 is EXTERNAL1
*
* CS1 PI10
* CS2 PA15
* DRDY1 PD11
* DRDY2 PD12
*
*/
#define PX4_SPI_BUS_SENSORS1 1
#define PX4_SPI_BUS_SENSORS2 2
#define PX4_SPI_BUS_SENSORS3 3
#define PX4_SPI_BUS_MAG 4
#define PX4_SPI_BUS_MEMORY 5
#define PX4_SPI_BUS_EXTERNAL1 6
/* Define the Chip Selects, Data Ready and Control signals per SPI bus */
/* SPI 1 CS */
#define GPIO_SPI1_nCS1_ICM20602 /* PI9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN9)
/* Define the SPI1 Data Ready interrupts */
#define GPIO_SPI1_DRDY1_ICM20602 /* PF2 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTF|GPIO_PIN2)
/* 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_ICM20602 _PIN_OFF(GPIO_SPI1_DRDY1_ICM20602)
/* SPI 2 CS */
#define GPIO_SPI2_nCS1_ISM330 /* PH5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5)
/* Define the SPI2 Data Ready interrupts */
#define GPIO_SPI2_DRDY1_ISM330 /* PH12 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTH|GPIO_PIN12)
/* SPI2 off */
#define GPIO_SPI2_SCK_OFF _PIN_OFF(GPIO_SPI2_SCK)
#define GPIO_SPI2_MISO_OFF _PIN_OFF(GPIO_SPI2_MISO)
#define GPIO_SPI2_MOSI_OFF _PIN_OFF(GPIO_SPI2_MOSI)
#define GPIO_DRDY_OFF_SPI2_DRDY1_ISM330 _PIN_OFF(GPIO_SPI2_DRDY1_ISM330)
/* SPI 3 CS */
#define GPIO_SPI3_nCS1_BMI088_ACCEL /* PI4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN4)
#define GPIO_SPI3_nCS2_BMI088_GYRO /* PI8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN8)
/* Define the SPI3 Data Ready interrupts */
#define GPIO_SPI3_DRDY1_BMI088_INT1_ACCEL /* PI6 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTI|GPIO_PIN6)
#define GPIO_SPI3_DRDY2_BMI088_INT3_GYRO /* PI7 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTI|GPIO_PIN7)
/* SPI3 off */
#define GPIO_SPI3_SCK_OFF _PIN_OFF(GPIO_SPI3_SCK)
#define GPIO_SPI3_MISO_OFF _PIN_OFF(GPIO_SPI3_MISO)
#define GPIO_SPI3_MOSI_OFF _PIN_OFF(GPIO_SPI3_MOSI)
#define GPIO_DRDY_OFF_SPI3_DRDY1_BMI088 _PIN_OFF(GPIO_SPI3_DRDY1_BMI088_INT1_ACCEL)
#define GPIO_DRDY_OFF_SPI3_DRDY2_BMI088 _PIN_OFF(GPIO_SPI3_DRDY2_BMI088_INT3_GYRO)
/* SPI 4 CS */
#define GPIO_SPI4_nCS1_BMM150 /* PH15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN15)
/* Define the SPI4 Data Ready interrupts */
#define GPIO_SPI4_DRDY1_BMM150 /* PF3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTF|GPIO_PIN3)
/* SPI4 off */
#define GPIO_SPI4_SCK_OFF _PIN_OFF(GPIO_SPI4_SCK)
#define GPIO_SPI4_MISO_OFF _PIN_OFF(GPIO_SPI4_MISO)
#define GPIO_SPI4_MOSI_OFF _PIN_OFF(GPIO_SPI4_MOSI)
#define GPIO_DRDY_OFF_SPI4_DRDY1_BMM150 _PIN_OFF(GPIO_SPI4_DRDY1_BMM150)
/* SPI 5 CS */
#define GPIO_SPI5_nCS1_FRAM /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN7)
/* SPI 6 */
#define GPIO_SPI6_nCS1_EXTERNAL1 /* PI10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN10)
#define GPIO_SPI6_nCS2_EXTERNAL1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN15)
/* Define the SPI6 Data Ready interrupts */
#define GPIO_SPI6_DRDY1_EXTERNAL1 /* PD11 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN11)
#define GPIO_SPI6_DRDY2_EXTERNAL1 /* PD12 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN12)
/* SPI6 off */
#define GPIO_SPI6_SCK_OFF _PIN_OFF(GPIO_SPI6_SCK)
#define GPIO_SPI6_MISO_OFF _PIN_OFF(GPIO_SPI6_MISO)
#define GPIO_SPI6_MOSI_OFF _PIN_OFF(GPIO_SPI6_MOSI)
#define GPIO_DRDY_OFF_SPI6_DRDY1 _PIN_OFF(GPIO_SPI6_DRDY1_EXTERNAL1)
#define GPIO_DRDY_OFF_SPI6_DRDY2 _PIN_OFF(GPIO_SPI6_DRDY2_EXTERNAL1)
/*
* 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 PX4_SPI_BUS_RAMTRON PX4_SPI_BUS_MEMORY
#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS1,0)
#define PX4_SENSORS1_BUS_CS_GPIO {GPIO_SPI1_nCS1_ICM20602}
#define PX4_SPIDEV_ISM330 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS2,0)
#define PX4_SENSORS2_BUS_CS_GPIO {GPIO_SPI2_nCS1_ISM330}
#define PX4_SPIDEV_BMI055_GYR PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS3,0)
#define PX4_SPIDEV_BMI055_ACC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS3,1)
#define PX4_SENSORS3_BUS_CS_GPIO {GPIO_SPI3_nCS2_BMI088_GYRO, GPIO_SPI3_nCS1_BMI088_ACCEL}
#define PX4_SPIDEV_BMM150 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS4,0)
#define PX4_SENSORS4_BUS_CS_GPIO {GPIO_SPI4_nCS1_BMM150}
#define PX4_SPIDEV_MEMORY PX4_MK_SPI_SEL(PX4_SPI_BUS_MEMORY,0)
#define PX4_MEMORY_BUS_CS_GPIO {GPIO_SPI5_nCS1_FRAM}
#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 {GPIO_SPI6_nCS1_EXTERNAL1, GPIO_SPI6_nCS2_EXTERNAL1}
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
#define PX4_I2C_BUS_EXPANSION1 2
#define PX4_I2C_BUS_EXPANSION2 3
#define PX4_I2C_BUS_ONBOARD 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}
#define GPIO_I2C4_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5)
#define A71CH_nRST /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN6)
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that
* can be used by the Px4 Firmware in the adc driver
*/
/* ADC defines to be used in sensors.cpp to read from a particular channel */
#define ADC1_CH(n) (n)
#define ADC1_GPIO(n) GPIO_ADC1_IN##n
#define ADC3_CH(n) (n)
#define ADC3_GPIO(n) GPIO_ADC3_IN##n
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
#define PX4_ADC_GPIO \
/* PA0 */ ADC1_GPIO(0), \
/* PA4 */ ADC1_GPIO(4), \
/* PB0 */ ADC1_GPIO(8), \
/* PB1 */ ADC1_GPIO(9), \
/* PC0 */ ADC1_GPIO(10), \
/* PC2 */ ADC1_GPIO(12), \
/* PC3 */ ADC1_GPIO(13), \
/* PF4 */ ADC3_GPIO(14), \
/* PF5 */ ADC3_GPIO(15)
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(0)
#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* PA4 */ ADC1_CH(4)
#define ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL /* PB0 */ ADC1_CH(8)
#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(9)
#define ADC_ADC1_6V6_CHANNEL /* PC0 */ ADC1_CH(10)
#define ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL /* PC2 */ ADC1_CH(12)
#define ADC_ADC1_3V3_CHANNEL /* PC3 */ ADC1_CH(13)
#define ADC_HW_VER_SENSE_CHANNEL /* PF4 */ ADC3_CH(14)
#define ADC_HW_REV_SENSE_CHANNEL /* PF5 */ ADC3_CH(15)
#define ADC_CHANNELS \
((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL) | \
(1 << ADC_SCALED_V5_CHANNEL) | \
(1 << ADC_ADC1_6V6_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL) | \
(1 << ADC_ADC1_3V3_CHANNEL) | \
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
(1 << ADC_HW_REV_SENSE_CHANNEL))
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_REV_SENSE /* PF5 */ ADC3_CH(15)
#define GPIO_HW_VER_SENSE /* PF4 */ ADC3_CH(14)
#define HW_INFO_INIT {'V','5','X','x', 'x',0}
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
/* HEATER
* PWM in future
*/
#define GPIO_HEATER_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
/* PWM Capture
*
* 1 PWM Capture inputs are configured.
*
* Pins:
*
* FMU_CAP1 : PI0 : TIM5_CH4
*/
#define GPIO_TIM5_CH4IN /* PI0 T5C4 FMU_CAP1 */ GPIO_TIM5_CH4IN_2
#define GPIO_TIM5_CH4OUT /* PI0 T5C4 FMU_CAP1 */ GPIO_TIM5_CH4OUT_2
#define DIRECT_PWM_CAPTURE_CHANNELS 1
/* PC12 is nARMED
* The GPIO will be set as input while not armed HW will have external HW Pull UP.
* While armed it shall be configured at a GPIO OUT set LOW
*/
#define GPIO_nARMED_INIT /* PC12 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN12)
#define GPIO_nARMED /* PC12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN12)
#if !defined(TRACE_PINS)
# define BOARD_INDICATE_ARMED_STATE(on_armed) px4_arch_configgpio((on_armed) ? GPIO_nARMED : GPIO_nARMED_INIT)
#endif
/* PWM
*
* 8 PWM outputs are configured.
*
* Pins:
*
* FMU_CH1 : PE14 : TIM1_CH4
* FMU_CH2 : PA10 : TIM1_CH3
* FMU_CH3 : PE11 : TIM1_CH2
* FMU_CH4 : PA8 : TIM1_CH1
* FMU_CH5 : PD13 : TIM4_CH2
* FMU_CH6 : PD14 : TIM4_CH3
* FMU_CH7 : PH6 : TIM12_CH1
* FMU_CH8 : PH9 : TIM12_CH2
*
*/
#define GPIO_TIM12_CH2OUT /* PH9 T12C2 FMU8 */ GPIO_TIM12_CH2OUT_2
#define GPIO_TIM12_CH1OUT /* PH6 T12C1 FMU7 */ GPIO_TIM12_CH1OUT_2
#define GPIO_TIM4_CH3OUT /* PD14 T4C3 FMU6 */ GPIO_TIM4_CH3OUT_2
#define GPIO_TIM4_CH2OUT /* PD13 T4C2 FMU5 */ GPIO_TIM4_CH2OUT_2
#define GPIO_TIM1_CH1OUT /* PA8 T1C1 FMU4 */ GPIO_TIM1_CH1OUT_1
#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 8
#define GPIO_TIM12_CH2IN /* PH9 T12C2 FMU8 */ GPIO_TIM12_CH2IN_2
#define GPIO_TIM12_CH1IN /* PH6 T12C1 FMU7 */ GPIO_TIM12_CH1IN_2
#define GPIO_TIM4_CH3IN /* PD14 T4C3 FMU6 */ GPIO_TIM4_CH3IN_2
#define GPIO_TIM4_CH2IN /* PD13 T4C2 FMU5 */ GPIO_TIM4_CH2IN_2
#define GPIO_TIM1_CH1IN /* PA8 T1C1 FMU4 */ GPIO_TIM1_CH1IN_1
#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 8
/* User GPIOs
*
* GPIO0-5 are the PWM servo outputs.
*/
#define _MK_GPIO_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLUP))
#define GPIO_GPIO7_INPUT /* PH9 T12C2 FMU8 */ _MK_GPIO_INPUT(GPIO_TIM12_CH2IN)
#define GPIO_GPIO6_INPUT /* PH6 T12C1 FMU7 */ _MK_GPIO_INPUT(GPIO_TIM12_CH1IN)
#define GPIO_GPIO5_INPUT /* PD14 T4C3 FMU6 */ _MK_GPIO_INPUT(GPIO_TIM4_CH3IN)
#define GPIO_GPIO4_INPUT /* PD13 T4C2 FMU5 */ _MK_GPIO_INPUT(GPIO_TIM4_CH2IN)
#define GPIO_GPIO3_INPUT /* PA8 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_GPIO7_OUTPUT /* PH9 T12C2 FMU8 */ _MK_GPIO_OUTPUT(GPIO_TIM12_CH2OUT)
#define GPIO_GPIO6_OUTPUT /* PH6 T12C1 FMU7 */ _MK_GPIO_OUTPUT(GPIO_TIM12_CH1OUT)
#define GPIO_GPIO5_OUTPUT /* PD14 T4C3 FMU6 */ _MK_GPIO_OUTPUT(GPIO_TIM4_CH3OUT)
#define GPIO_GPIO4_OUTPUT /* PD13 T4C2 FMU5 */ _MK_GPIO_OUTPUT(GPIO_TIM4_CH2OUT)
#define GPIO_GPIO3_OUTPUT /* PA8 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 BOARD_NUMBER_DIGITAL_BRICKS 2
#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */
#define GPIO_VDD_5V_PERIPH_nEN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4)
#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15)
#define GPIO_VDD_5V_HIPOWER_nEN /* PF12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN12)
#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_PULLUP|GPIO_PORTF|GPIO_PIN13)
#define GPIO_VDD_3V3_SENSORS1_EN /* PI11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN11)
#define GPIO_VDD_3V3_SENSORS2_EN /* PD15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15)
#define GPIO_VDD_3V3_SENSORS3_EN /* PE7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN7)
#define GPIO_VDD_3V3_SENSORS4_EN /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8)
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2)
#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
/* Spare GPIO */
#define GPIO_PH11 /* PH11 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTH|GPIO_PIN1)
/* ETHERNET GPIO */
#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15)
/* NFC GPIO */
#define GPIO_NFC_GPIO /* PH3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTH|GPIO_PIN3)
/* Define True logic Power Control in arch agnostic form */
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true))
#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true))
#define VDD_3V3_SENSORS1_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS1_EN, (on_true))
#define VDD_3V3_SENSORS2_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS2_EN, (on_true))
#define VDD_3V3_SENSORS3_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS3_EN, (on_true))
#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_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 14 /* Timer 14 */
#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */
#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9)
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
#define GPIO_TONE_ALARM GPIO_TIM14_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 */
#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
#define RC_UXART_BASE STM32_USART6_BASE
#define RC_SERIAL_PORT "/dev/ttyS5"
#define BOARD_HAS_SINGLE_WIRE 1 /* HW is capable of Single Wire */
#define BOARD_HAS_SINGLE_WIRE_ON_TX 0 /* HW default is wired as Single Wire On RX pin */
#define BOARD_HAS_RX_TX_SWAP 1 /* HW Can swap TX and RX */
#define RC_SERIAL_PORT_IS_SWAPED 1 /* Board wired with RC's TX is on cpu RX */
/* Input Capture Channels. */
#define INPUT_CAP1_TIMER 5
#define INPUT_CAP1_CHANNEL /* T5C4 */ 4
#define GPIO_INPUT_CAP1 /* PI0 */ GPIO_TIM5_CH4_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
/* Safety Switch is HW version dependent on having an PX4IO
* So we init to a benign state with the _INIT definition
* and provide the the non _INIT one for the driver to make a run time
* decision to use it.
*/
#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN10)
#define GPIO_nSAFETY_SWITCH_LED_OUT /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */
#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT
#define GPIO_SAFETY_SWITCH_IN /* PH4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTH|GPIO_PIN4)
/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */
#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */
/* Power switch controls ******************************************************/
#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true)
/*
* FMUv5X has a separate RC_IN
*
* GPIO PPM_IN on PI5 T8CH1
* SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7
* Inversion is possible in the UART and can drive GPIO PPM_IN as an output
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define SDIO_SLOTNO 1 /* Only one slot */
#define SDIO_MINOR 1
/* 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))
/* FMUv5X never powers off the Servo rail */
#define BOARD_ADC_SERVO_VALID (1)
#if !defined(BOARD_HAS_LTC44XX_VALIDS) || BOARD_HAS_LTC44XX_VALIDS == 0
# define BOARD_ADC_BRICK1_VALID (1)
# define BOARD_ADC_BRICK2_VALID (0)
#elif BOARD_HAS_LTC44XX_VALIDS == 1
# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
# define BOARD_ADC_BRICK2_VALID (0)
#elif BOARD_HAS_LTC44XX_VALIDS == 2
# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
#elif BOARD_HAS_LTC44XX_VALIDS == 3
# 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_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID))
#elif BOARD_HAS_LTC44XX_VALIDS == 4
# 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_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID))
# define BOARD_ADC_BRICK4_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK4_VALID))
#else
# error Unsupported BOARD_HAS_LTC44XX_VALIDS value
#endif
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC))
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC))
#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_GPIO7_INPUT, \
GPIO_GPIO6_INPUT, \
GPIO_GPIO5_INPUT, \
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_VER_REV_DRIVE, \
GPIO_CAN1_TX, \
GPIO_CAN1_RX, \
GPIO_CAN2_TX, \
GPIO_CAN2_RX, \
GPIO_HEATER_OUTPUT, \
GPIO_nPOWER_IN_A, \
GPIO_nPOWER_IN_B, \
GPIO_nPOWER_IN_C, \
GPIO_VDD_5V_PERIPH_nEN, \
GPIO_VDD_5V_PERIPH_nOC, \
GPIO_VDD_5V_HIPOWER_nEN, \
GPIO_VDD_5V_HIPOWER_nOC, \
GPIO_VDD_3V3_SENSORS1_EN, \
GPIO_VDD_3V3_SENSORS2_EN, \
GPIO_VDD_3V3_SENSORS3_EN, \
GPIO_VDD_3V3_SENSORS4_EN, \
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
GPIO_VDD_3V3_SD_CARD_EN, \
GPIO_PH11, \
GPIO_ETH_POWER_EN, \
GPIO_NFC_GPIO, \
GPIO_TONE_ALARM_IDLE, \
GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \
GPIO_SAFETY_SWITCH_IN, \
GPIO_nARMED_INIT \
}
#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 PX4FMU 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 <drivers/boards/common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS

View File

@ -0,0 +1,123 @@
/****************************************************************************
*
* 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"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration ********************************************************************/
#if defined(CONFIG_STM32F7_CAN1) && defined(CONFIG_STM32F7_CAN2)
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
# undef CONFIG_STM32F7_CAN2
#endif
#ifdef CONFIG_STM32F7_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 /* CONFIG_CAN */

View File

@ -0,0 +1,356 @@
/****************************************************************************
*
* 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 initialization.
*/
/****************************************************************************
* 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/i2c/i2c_master.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_init.h>
#include <drivers/boards/common/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_rc_input
*
* Description:
* All boards my optionally provide this API to invert the Serial RC input.
* This is needed on SoCs that support the notion RXINV or TXINV as apposed to
* and external XOR controlled by a GPIO
*
************************************************************************************/
__EXPORT void board_rc_input(bool invert_on, uint32_t uxart_base)
{
irqstate_t irqstate = px4_enter_critical_section();
uint32_t cr1 = getreg32(STM32_USART_CR1_OFFSET + uxart_base);
uint32_t cr2 = getreg32(STM32_USART_CR2_OFFSET + uxart_base);
uint32_t regval = cr1;
/* {R|T}XINV bit fields can only be written when the USART is disabled (UE=0). */
regval &= ~USART_CR1_UE;
putreg32(regval, STM32_USART_CR1_OFFSET + uxart_base);
if (invert_on) {
#if defined(BOARD_HAS_RX_TX_SWAP) && RC_SERIAL_PORT_IS_SWAPED == 1
/* This is only ever turned on */
cr2 |= (USART_CR2_RXINV | USART_CR2_TXINV | USART_CR2_SWAP);
#else
cr2 |= (USART_CR2_RXINV | USART_CR2_TXINV);
#endif
} else {
cr2 &= ~(USART_CR2_RXINV | USART_CR2_TXINV);
}
putreg32(cr2, STM32_USART_CR2_OFFSET + uxart_base);
putreg32(cr1, STM32_USART_CR1_OFFSET + uxart_base);
leave_critical_section(irqstate);
}
/************************************************************************************
* Name: board_peripheral_reset
*
* Description:
*
************************************************************************************/
__EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
VDD_5V_PERIPH_EN(false);
VDD_3V3_SENSORS1_EN(false);
VDD_3V3_SENSORS2_EN(false);
VDD_3V3_SENSORS3_EN(false);
VDD_3V3_SENSORS4_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_SENSORS1_EN(true);
VDD_3V3_SENSORS2_EN(true);
VDD_3V3_SENSORS3_EN(true);
VDD_3V3_SENSORS4_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;
board_gpio_init(gpio, arraySize(gpio));
if (status >= 0) {
up_mdelay(6);
}
}
/****************************************************************************
* Name: board_app_finalinitialize
*
* 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_FINALINIT.
*
* Input Parameters:
* arg - The argument has no meaning.
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
#ifdef CONFIG_BOARDCTL_FINALINIT
int board_app_finalinitialize(uintptr_t arg)
{
board_configure_dcache(1);
return 0;
}
#endif
/************************************************************************************
* 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;
board_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 */
board_configure_dcache(0);
VDD_3V3_SD_CARD_EN(true);
VDD_5V_PERIPH_EN(true);
VDD_5V_HIPOWER_EN(true);
VDD_3V3_SENSORS1_EN(true);
VDD_3V3_SENSORS2_EN(true);
VDD_3V3_SENSORS3_EN(true);
VDD_3V3_SENSORS4_EN(true);
VDD_3V3_SPEKTRUM_POWER_EN(true);
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");
}
px4_platform_init();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
/* 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);
/* 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;
}

View File

@ -0,0 +1,232 @@
/****************************************************************************
*
* 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_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
GPIO_nSAFETY_SWITCH_LED_OUT_INIT, // Indexed by LED_SAFETY (defaulted to an input)
GPIO_nLED_GREEN, // Indexed by LED_GREEN
};
#endif
__EXPORT void led_init(void)
{
/* Configure LED GPIOs for output */
if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_PX4IO)) {
g_ledmap[2] = GPIO_nSAFETY_SWITCH_LED_OUT;
}
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
stm32_configgpio(g_ledmap[l]);
}
}
static void phy_set_led(int led, bool state)
{
/* Drive Low to switch on */
stm32_gpiowrite(g_ledmap[led], !state);
}
static bool phy_get_led(int led)
{
/* If Low it is on */
return !stm32_gpioread(g_ledmap[led]);
}
__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 */

View File

@ -0,0 +1,153 @@
/****************************************************************************
*
* 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_v0500[] = {
{
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
};
static const px4_hw_mft_item_t hw_mft_list_v0501[] = {
{
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
};
static px4_hw_mft_list_entry_t mft_lists[] = {
{0x0000, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
{0x0001, hw_mft_list_v0501, arraySize(hw_mft_list_v0501)},
};
/************************************************************************************
* Name: board_rc_input
*
* Description:
* All boards my optionally provide this API to invert the Serial RC input.
* This is needed on SoCs that support the notion RXINV or TXINV as opposed to
* and external XOR controlled by a GPIO
*
************************************************************************************/
__EXPORT bool board_supports_single_wire(uint32_t uxart_base)
{
return uxart_base == RC_UXART_BASE;
}
/************************************************************************************
* 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;
}

View File

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

View File

@ -0,0 +1,449 @@
/****************************************************************************
*
* 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 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_SENSORS1_BUS_CS_GPIO;
static constexpr uint32_t spi2selects_gpio[] = PX4_SENSORS2_BUS_CS_GPIO;
static constexpr uint32_t spi3selects_gpio[] = PX4_SENSORS3_BUS_CS_GPIO;
static constexpr uint32_t spi4selects_gpio[] = PX4_SENSORS4_BUS_CS_GPIO;
static constexpr uint32_t spi5selects_gpio[] = PX4_MEMORY_BUS_CS_GPIO;
static constexpr uint32_t spi6selects_gpio[] = PX4_EXTERNAL1_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_STM32F7_SPI1
for (auto gpio : spi1selects_gpio) {
px4_arch_configgpio(gpio);
}
#endif // CONFIG_STM32F7_SPI1
#if defined(CONFIG_STM32F7_SPI2)
for (auto gpio : spi2selects_gpio) {
px4_arch_configgpio(gpio);
}
#endif // CONFIG_STM32F7_SPI2
#if defined(CONFIG_STM32F7_SPI3)
for (auto gpio : spi3selects_gpio) {
px4_arch_configgpio(gpio);
}
#endif // CONFIG_STM32F7_SPI3
#ifdef CONFIG_STM32F7_SPI4
for (auto gpio : spi4selects_gpio) {
px4_arch_configgpio(gpio);
}
#endif // CONFIG_STM32F7_SPI4
#ifdef CONFIG_STM32F7_SPI5
for (auto gpio : spi5selects_gpio) {
px4_arch_configgpio(gpio);
}
#endif // CONFIG_STM32F7_SPI5
#ifdef CONFIG_STM32F7_SPI6
for (auto gpio : spi6selects_gpio) {
px4_arch_configgpio(gpio);
}
#endif // CONFIG_STM32F7_SPI6
}
/************************************************************************************
* Name: stm32_spi1select and stm32_spi1status
*
* Description:
* Called by stm32 spi driver on bus 1.
*
************************************************************************************/
#ifdef CONFIG_STM32F7_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_SENSORS1);
// 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_STM32F7_SPI1
/************************************************************************************
* Name: stm32_spi2select and stm32_spi2status
*
* Description:
* Called by stm32 spi driver on bus 2.
*
************************************************************************************/
#if defined(CONFIG_STM32F7_SPI2)
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_SENSORS2);
// 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_STM32F7_SPI2
/************************************************************************************
* Name: stm32_spi3select and stm32_spi3status
*
* Description:
* Called by stm32 spi driver on bus 3.
*
************************************************************************************/
#if defined(CONFIG_STM32F7_SPI3)
__EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_SENSORS3);
// Making sure the other peripherals are not selected
for (auto cs : spi3selects_gpio) {
stm32_gpiowrite(cs, 1);
}
// SPI select is active low, so write !selected to select the device
stm32_gpiowrite(spi3selects_gpio[PX4_SPI_DEV_ID(devid)], !selected);
}
__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif // CONFIG_STM32F7_SPI3
/************************************************************************************
* Name: stm32_spi4select and stm32_spi4status
*
* Description:
* Called by stm32 spi driver on bus 4.
*
************************************************************************************/
#ifdef CONFIG_STM32F7_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_SENSORS3);
// 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_STM32F7_SPI4
/************************************************************************************
* Name: stm32_spi5select and stm32_spi5status
*
* Description:
* Called by stm32 spi driver on bus 5.
*
************************************************************************************/
#ifdef CONFIG_STM32F7_SPI5
__EXPORT void stm32_spi5select(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 : 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_STM32F7_SPI5
/************************************************************************************
* Name: stm32_spi6select and stm32_spi6status
*
* Description:
* Called by stm32 spi driver on bus 6.
*
************************************************************************************/
#ifdef CONFIG_STM32F7_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_EXTERNAL1);
// 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_STM32F7_SPI6
/************************************************************************************
* Name: board_spi_reset
*
* Description:
* TODO:Add 4 bit MASK active LOW for Bus 1-4
*
************************************************************************************/
__EXPORT void board_spi_reset(int mask_ms)
{
int ms = mask_ms & 0x00ffffff;
int mask = ((mask_ms & 0xff000000) >> 24) ^ 0xff;
// disable SPI bus
if (mask & 1) {
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_ICM20602);
#endif
/* set the sensor rail off */
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS1_EN, 0);
}
if (mask & 2) {
for (auto cs : spi2selects_gpio) {
stm32_configgpio(_PIN_OFF(cs));
}
stm32_configgpio(GPIO_SPI2_SCK_OFF);
stm32_configgpio(GPIO_SPI2_MISO_OFF);
stm32_configgpio(GPIO_SPI2_MOSI_OFF);
#if BOARD_USE_DRDY
stm32_configgpio(GPIO_DRDY_OFF_SPI2_DRDY1_ISM330);
#endif
/* set the sensor rail off */
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS2_EN, 0);
}
if (mask & 4) {
for (auto cs : spi3selects_gpio) {
stm32_configgpio(_PIN_OFF(cs));
}
stm32_configgpio(GPIO_SPI3_SCK_OFF);
stm32_configgpio(GPIO_SPI3_MISO_OFF);
stm32_configgpio(GPIO_SPI3_MOSI_OFF);
#if BOARD_USE_DRDY
stm32_configgpio(GPIO_DRDY_OFF_SPI3_DRDY1_BMI088);
stm32_configgpio(GPIO_DRDY_OFF_SPI3_DRDY2_BMI088);
#endif
/* set the sensor rail off */
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS3_EN, 0);
}
if (mask & 8) {
for (auto cs : spi4selects_gpio) {
stm32_configgpio(_PIN_OFF(cs));
}
stm32_configgpio(GPIO_SPI4_SCK_OFF);
stm32_configgpio(GPIO_SPI4_MISO_OFF);
stm32_configgpio(GPIO_SPI4_MOSI_OFF);
#if BOARD_USE_DRDY
stm32_configgpio(GPIO_DRDY_OFF_SPI4_DRDY1_BMM150);
#endif
/* set the sensor rail off */
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS4_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_SENSORS1_EN, 1);
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS2_EN, 1);
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS3_EN, 1);
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, 1);
/* wait a bit before starting SPI, different times didn't influence results */
usleep(100);
if (mask & 1) {
/* 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_ICM20602);
#endif
}
if (mask & 2) {
/* reconfigure the SPI pins */
for (auto cs : spi2selects_gpio) {
stm32_configgpio(cs);
}
stm32_configgpio(GPIO_SPI2_SCK);
stm32_configgpio(GPIO_SPI2_MISO);
stm32_configgpio(GPIO_SPI2_MOSI);
#if BOARD_USE_DRDY
stm32_configgpio(GPIO_SPI2_DRDY1_ISM330);
#endif
}
if (mask & 4) {
/* reconfigure the SPI pins */
for (auto cs : spi3selects_gpio) {
stm32_configgpio(cs);
}
stm32_configgpio(GPIO_SPI3_SCK);
stm32_configgpio(GPIO_SPI3_MISO);
stm32_configgpio(GPIO_SPI3_MOSI);
#if BOARD_USE_DRDY
stm32_configgpio(GPIO_SPI3_DRDY1_BMI088);
stm32_configgpio(GPIO_SPI3_DRDY2_BMI088);
#endif
}
if (mask & 8) {
/* reconfigure the SPI pins */
for (auto cs : spi4selects_gpio) {
stm32_configgpio(cs);
}
stm32_configgpio(GPIO_SPI4_SCK);
stm32_configgpio(GPIO_SPI4_MISO);
stm32_configgpio(GPIO_SPI4_MOSI);
#if BOARD_USE_DRDY
stm32_configgpio(GPIO_SPI4_DRDY1_BMM150);
#endif
}
}

View File

@ -0,0 +1,230 @@
/****************************************************************************
*
* 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 <drivers/stm32/drv_io_timer.h>
#include "board_config.h"
/* Timer allocation
*
* TIM1_CH4 T FMU_CH1
* TIM1_CH3 T FMU_CH2
* TIM1_CH2 T FMU_CH3
* TIM1_CH1 T FMU_CH4
*
* TIM4_CH2 T FMU_CH5
* TIM4_CH3 T FMU_CH6
*
* TIM12_CH1 T FMU_CH7
* TIM12_CH2 T FMU_CH8
*
* TIM5_CH4 T FMU_CAP1 < Capture
* TIM5_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT
* TIM5_CH1 T SPIX_SYNC > Pulse or GPIO strobe
* TIM2_CH3 T HEATER > PWM OUT or GPIO
*
* TIM14_CH1 T BUZZER_1 - Driven by other driver
* TIM8_CH1_IN T FMU_PPM_INPUT - Sampled byt HRT by other driver
*/
__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_TIM1CC,
},
{
.base = STM32_TIM4_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM4EN,
.clock_freq = STM32_APB1_TIM4_CLKIN,
.first_channel_index = 4,
.last_channel_index = 5,
.handler = io_timer_handler1,
.vectorno = STM32_IRQ_TIM4,
},
{
.base = STM32_TIM12_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM12EN,
.clock_freq = STM32_APB1_TIM12_CLKIN,
.first_channel_index = 6,
.last_channel_index = 7,
.handler = io_timer_handler2,
.vectorno = STM32_IRQ_TIM12,
},
{
.base = STM32_TIM5_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM5EN,
.clock_freq = STM32_APB1_TIM5_CLKIN,
.first_channel_index = 8,
.last_channel_index = 10,
.handler = io_timer_handler3,
.vectorno = STM32_IRQ_TIM5,
},
{
.base = STM32_TIM2_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM2EN,
.clock_freq = STM32_APB1_TIM2_CLKIN,
.first_channel_index = 11,
.last_channel_index = 11,
.handler = io_timer_handler4,
.vectorno = STM32_IRQ_TIM2,
},
};
__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
},
{
.gpio_out = GPIO_TIM4_CH3OUT,
.gpio_in = GPIO_TIM4_CH3IN,
.timer_index = 1,
.timer_channel = 3,
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
},
{
.gpio_out = GPIO_TIM12_CH1OUT,
.gpio_in = GPIO_TIM12_CH1IN,
.timer_index = 2,
.timer_channel = 1,
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
},
{
.gpio_out = GPIO_TIM12_CH2OUT,
.gpio_in = GPIO_TIM12_CH2IN,
.timer_index = 2,
.timer_channel = 2,
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
},
// todo:Need to support MAX_TIMER_IO_CHANNELS == 12
#if MAX_TIMER_IO_CHANNELS == 12
{
.gpio_out = GPIO_TIM5_CH4OUT,
.gpio_in = GPIO_TIM5_CH4IN,
.timer_index = 3,
.timer_channel = 4,
.ccr_offset = STM32_GTIM_CCR4_OFFSET,
.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF
},
{
.gpio_out = 0,
.gpio_in = GPIO_TIM5_CH3IN,
.timer_index = 3,
.timer_channel = 3,
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
},
{
.gpio_out = GPIO_TIM5_CH1OUT,
.gpio_in = 0,
.timer_index = 3,
.timer_channel = 1,
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
},
{
.gpio_out = GPIO_TIM2_CH3OUT,
.gpio_in = 0,
.timer_index = 4,
.timer_channel = 3,
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
}
#endif
};

View File

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

View File

@ -0,0 +1,130 @@
px4_add_board(
PLATFORM nuttx
VENDOR px4
MODEL fmu-v5x
LABEL stackcheck
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
IO px4_io-v2_default
TESTING
#UAVCAN_INTERFACES 2
SERIAL_PORTS
GPS1:/dev/ttyS1
TEL1:/dev/ttyS6
TEL2:/dev/ttyS4
TEL3:/dev/ttyS2
GPS2:/dev/ttyS0
DRIVERS
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
gps
#heater
imu/adis16448
imu/adis16497
#imu # all available imu drivers
# TBD imu/bmi088 - needs bus selection
# TBD imu/ism330dlc - needs bus selection
imu/mpu6000
#irlock
#lights/blinkm
#lights/oreoled
lights/pca8574
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
pwm_out_sim
px4fmu
px4io
rc_input
roboclaw
stm32
stm32/adc
stm32/armv7-m_dcache
stm32/tone_alarm
tap_esc
telemetry # all available telemetry drivers
test_ppm
tone_alarm
#uavcan
MODULES
attitude_estimator_q
camera_feedback
commander
dataman
ekf2
events
fw_att_control
fw_pos_control_l1
gnd_att_control
gnd_pos_control
land_detector
landing_target_estimator
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_pos_control
navigator
sensors
sih
vmount
vtol_att_control
wind_estimator
SYSTEMCMDS
bl_update
config
dmesg
dumpfile
esc_calib
hardfault_log
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
EXAMPLES
#bottle_drop # OBC challenge
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
#hello
#hwtest # Hardware test
#matlab_csv_serial
#position_estimator_inav
#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
#segway
#uuv_example_app
)