Adding px4nucleoF767ZI-v1

This commit is contained in:
David Sidrane 2016-12-12 12:25:13 -10:00 committed by Lorenz Meier
parent bca8767981
commit 6ce7ade2c6
20 changed files with 5036 additions and 0 deletions

View File

@ -0,0 +1,12 @@
{
"board_id": 90,
"magic": "PX4FWv1",
"description": "Firmware for the ST nucleo-144 with STM32FF767ZI-v1 board",
"image": "",
"build_time": 0,
"summary": "PX4NUCLEOF767ZIv1",
"version": "0.1",
"image_size": 0,
"git_identity": "",
"board_revision": 0
}

View File

@ -0,0 +1,199 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m7 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
set(config_uavcan_num_ifaces 2)
set(config_module_list
#
# Board support modules
#
drivers/device
drivers/stm32
drivers/stm32/adc
drivers/stm32/tone_alarm
drivers/led
drivers/px4fmu
drivers/boards/px4nucleoF767ZI-v1
drivers/rgbled
drivers/mpu6000
drivers/mpu9250
drivers/hmc5883
drivers/ms5611
drivers/mb12xx
drivers/srf02
drivers/sf0x
drivers/ll40ls
drivers/trone
drivers/gps
drivers/pwm_out_sim
drivers/hott
drivers/hott/hott_telemetry
drivers/hott/hott_sensors
drivers/blinkm
drivers/airspeed
drivers/ets_airspeed
drivers/meas_airspeed
drivers/frsky_telemetry
modules/sensors
drivers/mkblctrl
drivers/px4flow
drivers/oreoled
drivers/pwm_input
drivers/camera_trigger
drivers/bst
drivers/snapdragon_rc_pwm
drivers/lis3mdl
drivers/bmp280
drivers/bma180
drivers/bmi160
drivers/tap_esc
#
# System commands
#
systemcmds/bl_update
systemcmds/config
systemcmds/dumpfile
systemcmds/esc_calib
systemcmds/hardfault_log
systemcmds/mixer
systemcmds/motor_ramp
systemcmds/mtd
systemcmds/nshterm
systemcmds/param
systemcmds/perf
systemcmds/pwm
systemcmds/reboot
systemcmds/sd_bench
systemcmds/top
systemcmds/topic_listener
systemcmds/ver
#
# General system control
#
modules/commander
modules/load_mon
modules/navigator
modules/mavlink
modules/gpio_led
modules/uavcan
modules/land_detector
#
# Estimation modules
#
modules/attitude_estimator_q
modules/position_estimator_inav
modules/local_position_estimator
modules/ekf2
#
# Vehicle Control
#
# modules/segway # XXX Needs GCC 4.7 fix
modules/fw_pos_control_l1
modules/fw_att_control
modules/mc_att_control
modules/mc_pos_control
modules/vtol_att_control
#
# Logging
#
modules/logger
modules/sdlog2
#
# Library modules
#
modules/param
modules/systemlib
modules/systemlib/mixer
modules/uORB
modules/dataman
#
# Libraries
#
lib/controllib
lib/mathlib
lib/mathlib/math/filter
lib/rc
lib/ecl
lib/external_lgpl
lib/geo
lib/geo_lookup
lib/conversion
lib/launchdetection
lib/terrain_estimation
lib/runway_takeoff
lib/tailsitter_recovery
lib/DriverFramework/framework
platforms/nuttx
# had to add for cmake, not sure why wasn't in original config
platforms/common
platforms/nuttx/px4_layer
#
# OBC challenge
#
modules/bottle_drop
#
# Rover apps
#
examples/rover_steering_control
#
# Demo apps
#
#examples/math_demo
# Tutorial code from
# https://px4.io/dev/px4_simple_app
examples/px4_simple_app
# Tutorial code from
# https://px4.io/dev/daemon
#examples/px4_daemon_app
# Tutorial code from
# https://px4.io/dev/debug_values
#examples/px4_mavlink_debug
# Tutorial code from
# https://px4.io/dev/example_fixedwing_control
#examples/fixedwing_control
# Hardware test
#examples/hwtest
)
set(config_extra_builtin_cmds
serdis
sercon
)
set(config_extra_libs
uavcan
uavcan_stm32_driver
)
set(config_io_extra_libs
)
add_custom_target(sercon)
set_target_properties(sercon PROPERTIES
PRIORITY "SCHED_PRIORITY_DEFAULT"
MAIN "sercon"
STACK_MAIN "2048")
add_custom_target(serdis)
set_target_properties(serdis PROPERTIES
PRIORITY "SCHED_PRIORITY_DEFAULT"
MAIN "serdis"
STACK_MAIN "2048")

View File

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

View File

@ -0,0 +1,606 @@
/************************************************************************************
* nuttx-configs/px4nucleoF767ZI-v1/include/board.h
*
* Copyright (C) 2016 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_PX4NUCLEOF767ZI_V1_BOARD_HINCLUDE_BOARD_H
#define __NUTTX_CONFIG_PX4NUCLEOF767ZI_V1_BOARD_HINCLUDE_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 px4nucleoF767ZI-v1 board provides the following clock sources:
*
* MCO: 8 MHz from MCO output of ST-LINK is used as input clock
* X2: 32.768 KHz crystal for LSE
* X3: HSE crystal oscillator (not provided)
*
* So we have these clock source available within the STM32
*
* HSI: 16 MHz RC factory-trimmed
* LSI: 32 KHz RC
* HSE: 8 MHz from MCO output of ST-LINK
* LSE: 32.768 kHz
*/
#define STM32_BOARD_XTAL 8000000ul
#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
#define STM32_LSE_FREQUENCY 32768
/* Main PLL Configuration.
*
* PLL source is HSE = 8,000,000
*
* PLL_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 = (8,000,000 / 4) * 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(4)
#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 / 4) * 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_48MHZ
/* 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_SDIO_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_SDIO_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 Channl/Stream Selections *****************************************************/
/* Stream selections are arbitrary for now but might become important in the future
* if we set aside more DMA channels/streams.
*
* SDMMC DMA is on DMA2
*
* SDMMC1 DMA
* DMAMAP_SDMMC1_1 = Channel 4, Stream 3 <- may later be used by SPI DMA
* DMAMAP_SDMMC1_2 = Channel 4, Stream 6
*/
#define DMAMAP_SDMMC1 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 px4nucleoF767ZI-v1 board has numerous LEDs but only three, LD1 a Green LED, LD2 a Blue
* LED and LD3 a Red LED, that can be controlled by software. The following
* definitions assume the default Solder Bridges are installed.
*
* 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_GREEN BOARD_LED1
#define BOARD_LED_BLUE BOARD_LED2
#define BOARD_LED_RED 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.
*/
/* Button definitions ***************************************************************/
/* The STM32F7 Discovery supports one button: Pushbutton B1, labeled "User", is
* connected to GPIO PI11. A high value will be sensed when the button is depressed.
*/
#define BUTTON_USER 0
#define NUM_BUTTONS 1
#define BUTTON_USER_BIT (1 << BUTTON_USER)
/* Alternate function pin selections ************************************************/
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PB7[CN11-21] CONFLICT w/ BLUE LED*/
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PB6[CN12-17] */
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6[CN11-43] */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5[CN11-41] */
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4[CN11-39] */
#define GPIO_USART2_CTS GPIO_USART2_CTS_2 /* PD3[CN11-40] */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9[CN11-69] */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8[CN12-10] */
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12[CN12-43] */
#define GPIO_USART3_CTS GPIO_USART3_CTS_2 /* PD11[CN12-45] */
#if !defined(CONFIG_STM32F7_CAN1) && defined(CONFIG_STM32F7_UART4)
# define GPIO_UART4_RX GPIO_UART4_RX_4 /* PD0[CN11-57] */
# define GPIO_UART4_TX GPIO_UART4_TX_4 /* PD1[CN11-55] */
#endif
#define GPIO_USART6_RX GPIO_USART6_RX_2 /* PG9[CN11-63] */
#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14[CN12-61] */
#define GPIO_USART6_RTS GPIO_USART6_RTS_2 /* PG8[CN12-66] */
#define GPIO_USART6_CTT GPIO_USART6_CTS_2 /* PG15[CN11-64 */
#define GPIO_UART7_RX GPIO_UART7_RX_2 /* PF6[CN11-9] */
#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8[CN12-40] */
/* USART8:
*
* This configurations assume that you are connecting to the Morpho connector
* with the serial interface with the adaptor's RX on pin CN11 pin 64 and
* TX on pin CN11 pin 61
*
* USART8: has no remap
*
* GPIO_UART7_RX PE0[CN12-64]
* GPIO_UART7_TX PE1[CN11-61]
*/
/* UART RX DMA configurations */
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
/* CAN
*
* CAN1 is routed to the Morpho connector.
* CAN2 is routed to the Morpho connector.
* CAN3 is routed to the Morpho connector.
*/
/* The 144 pin package is conflicted with UART4 */
#if defined(CONFIG_STM32F7_CAN1) && !defined(CONFIG_STM32F7_UART4)
# define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0[CN11-57] */
# define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1[CN11-55] */
#endif
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12[CN12-16] */
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13[CN12-30] */
#define GPIO_CAN3_RX GPIO_CAN3_RX_1 /* PA8[CN12-23] */
#define GPIO_CAN3_TX GPIO_CAN3_TX_1 /* PA15[CN11-17] */
#if defined(CONFIG_STM32F7_CAN1) && defined(CONFIG_STM32F7_UART4)
#warning "On The 144 pin package CAN1 is conflicted with UART4!"
#endif
/* SPI
* N.B. 144 pinout limits access to SPI 2
* There are sensors on SPI1, and SPI4 is connected to the FRAM.
* BARO is on SPI5 for isolation.
* SPI6 Reserved
*
*/
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6[CN12-13] */
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7[CN11-45] */
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_3 /* PG11[CN11-79s] */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE13[CN12-55] */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE6[CN11-62] */
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE2[CN11-46] */
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8[CN11-54] */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF9[CN11-56] */
#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1 /* PF7[CN11-11] */
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12[CN11-65] */
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_3 /* PB5[CN12-29] */
#define GPIO_SPI6_SCK GPIO_SPI6_SCK_1 /* PG13[CN11-68] */
/* I2C
*
* Each I2C is associated with a U[S]ART
* hence the naming I2C2_SDA_UART4 in FMU USAGE spreadsheet
*
* PF1 can not be used on Morpho connector without SB mods.
* see PH1/PF1, SP148, SB163 On schematic
*
* I2C3 is not pined out on FMUv5 on 144 pin packages
*
* 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[CN12-3] */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9[CN12-5] */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTB | \
GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTB | \
GPIO_PIN9)
/* PF1 can not be used on Morpho connector without SB mods. */
#if defined(CONFIG_STM32F7_I2C2)
# warning "PF1 can not be used on Morpho connector without SB mods."
#endif
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1[CN11-51] */
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0[CN11-53] */
#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_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14[CN12-50] */
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15[CN12-60] */
#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_PIN14)
/* SDMMC1
*
* VDD 3.3 [CN11-5]
* GND [CN11-8]
* SDMMC1_CK PC12[CN11-3]
* SDMMC1_CMD PD2[CN11-4]
* SDMMC1_D0 PC8[CN12-2]
* SDMMC1_D1 PC9[CN12-1]
* SDMMC1_D2 PC10[CN11-1]
* SDMMC1_D3 PC11[CN11-2]
* GPIO_SDMMC1_NCD PG0[CN11-69]
*/
/* USB
*
* OTG_FS_DM PA11[CN12-14]
* OTG_FS_DP PA12[CN12-12]
* VBUS PA9[CN12-21]
*/
/* The STM32 F7 connects to a SMSC LAN8742A PHY using these pins:
*
* STM32 F7 BOARD LAN8742A
* GPIO SIGNAL PIN NAME
* -------- ------------ -------------
* PG11 RMII_TX_EN TXEN
* PG13 RMII_TXD0 TXD0
* PG14 RMII_TXD1 TXD1
* PC4 RMII_RXD0 RXD0/MODE0
* PC5 RMII_RXD1 RXD1/MODE1
* PG2 RMII_RXER RXER/PHYAD0 -- Not used
* PA7 RMII_CRS_DV CRS_DV/MODE2
* PC1 RMII_MDC MDC
* PA2 RMII_MDIO MDIO
* N/A NRST nRST
* PA1 RMII_REF_CLK nINT/REFCLK0
* N/A OSC_25M XTAL1/CLKIN
*
* The PHY address is either 0 or 1, depending on the state of PG2 on reset.
* PG2 is not controlled but appears to result in a PHY address of 0.
*/
#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_2
#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2
#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
#if defined(CONFIG_BOARD_USE_PROBES)
# 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[CN12-51] */
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13) /* PE13[CN12-55] */
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11[CN12-56] */
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) /* PE9[CN12-52] */
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13[CN12-41] */
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14[CN12-46] */
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
#else
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)
#endif
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
void stm32_boardinitialize(void);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /*__NUTTX_CONFIG_PX4NUCLEOF767ZI_V1_BOARD_HINCLUDE_BOARD_H */

View File

@ -0,0 +1,42 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
/**
* nsh_romfsetc.h
*
* This file is a stub for 'make export' purposes; the actual ROMFS
* must be supplied by the library client.
*/
extern unsigned char romfs_img[];
extern unsigned int romfs_img_len;

View File

@ -0,0 +1,166 @@
############################################################################
# nuttx-configs/px4nucleoF767ZI-v1/nsh/Make.defs
#
# Copyright (C) 2016 Gregory Nutt. All rights reserved.
# Authors: Gregory Nutt <gnutt@nuttx.org>
# 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.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include $(TOPDIR)/PX4_Warnings.mk
include $(TOPDIR)/PX4_Config.mk
#
# We only support building with the ARM bare-metal toolchain from
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
#
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI${HOST_OS_FIRST_LETTER}
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(ARCROSSDEV)ar rcs
NM = $(ARCROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
MAXOPTIMIZATION = -Os
# Enable precise stack overflow tracking
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
endif
# Pull in *just* libm from the toolchain ... this is grody
LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
EXTRA_LIBS += $(LIBM)
# Use our linker script
LDSCRIPT = ld.script
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mkwindeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
ifeq ($(PX4_WINTOOL),y)
# Windows-native toolchains (MSYS)
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
endif
# Tool versions
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
# Optimization flags
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
ARCHOPTIMIZATION += -g
endif
ifneq ($(CONFIG_DEBUG_NOOPT),y)
ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
endif
ARCHCFLAGS = --std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
ARCHWARNINGS = $(PX4_ARCHWARNINGS)
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# This seems to be the only way to add linker flags
EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
ASMEXT = .S
OBJEXT = .o
LIBEXT = .a
EXEEXT =
ifneq ($(CROSSDEV),arm-nuttx-elf-)
LDFLAGS += -nostartfiles -nodefaultlibs
endif
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
LDFLAGS += -g
endif
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe
HOSTLDFLAGS =

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,77 @@
#!/bin/bash
# nuttx-configs/px4nucleoF767ZI-v1/nsh/setenv.sh
#
# 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.
#
if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
WD=`pwd`
if [ ! -x "setenv.sh" ]; then
echo "This script must be executed from the top-level NuttX build directory"
exit 1
fi
if [ -z "${PATH_ORIG}" ]; then
export PATH_ORIG="${PATH}"
fi
# This is the Cygwin path to the location where I installed the Atmel GCC
# toolchain under Windows. You will also have to edit this if you install
# this toolchain in any other location
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/bin"
# This is the Cygwin path to the location where I installed the CodeSourcery
# toolchain under windows. You will also have to edit this if you install
# the CodeSourcery toolchain in any other location
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
# This is the path to the location where I installed the devkitARM toolchain
# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
# This is the Cygwin path to the location where I build the buildroot
# toolchain.
# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
# Add the path to the toolchain to the PATH varialble
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"

View File

@ -0,0 +1,179 @@
/****************************************************************************
* nuttx-configs/px4nucleoF767ZI-v1/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 STM32F767ZIT6 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 STM32F767ZIT6, 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 STM32F767ZIT6 will
* boot from address 0x0020:0000 in ITCM FLASH.
*
* The STM32F767ZIT6 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.
*/
MEMORY
{
itcm (rwx) : ORIGIN = 0x00200000, LENGTH = 2048K
flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K
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)
_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,86 @@
############################################################################
#
# Copyright (C) 2011 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.
#
############################################################################
-include $(TOPDIR)/Make.defs
CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = empty.c
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
OBJS = $(AOBJS) $(COBJS)
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
ifeq ($(WINTOOL),y)
CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
-I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
else
CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
endif
all: libboard$(LIBEXT)
$(AOBJS): %$(OBJEXT): %.S
$(call ASSEMBLE, $<, $@)
$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
$(call COMPILE, $<, $@)
libboard$(LIBEXT): $(OBJS)
$(call ARCHIVE, $@, $(OBJS))
.depend: Makefile $(SRCS)
$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
$(Q) touch $@
depend: .depend
clean:
$(call DELFILE, libboard$(LIBEXT))
$(call CLEAN)
distclean: clean
$(call DELFILE, Make.dep)
$(call DELFILE, .depend)
ifneq ($(BOARD_CONTEXT),y)
context:
endif
-include Make.dep

View File

@ -0,0 +1,4 @@
/*
* There are no source files here, but libboard.a can't be empty, so
* we have this empty source file to keep it company.
*/

View File

@ -0,0 +1,49 @@
############################################################################
#
# 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.
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4nucleoF767ZI-v1
COMPILE_FLAGS
-Os
SRCS
../common/board_name.c
../common/board_dma_alloc.c
# WIP px4nucleo_can.c
px4nucleo_init.c
px4nucleo_sdio.c
px4nucleo_timer_config.c
px4nucleo_spi.c
px4nucleo_usb.c
px4nucleo_led.c
DEPENDS
platforms__common
)

View File

@ -0,0 +1,402 @@
/****************************************************************************
*
* 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
*
* PX4NUCLEOF767ZI-v1 internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
__BEGIN_DECLS
/* these headers are not C++ safe */
#include <chip.h>
#include <stm32_gpio.h>
#include <arch/board/board.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
/* Configuration ************************************************************************************/
//{GPIO_RSSI_IN, 0, 0}, - pio Analog used as PWM
//{0, GPIO_LED_SAFETY, 0}, pio replacement
//{GPIO_SAFETY_SWITCH_IN, 0, 0}, pio replacement
//{0, GPIO_PERIPH_3V3_EN, 0}, Owned by the 8266 driver
//{0, GPIO_SBUS_INV, 0}, https://github.com/PX4/Firmware/blob/master/src/modules/px4iofirmware/sbus.c
//{GPIO_8266_GPIO0, 0, 0}, Owned by the 8266 driver
//{0, GPIO_SPEKTRUM_PWR_EN, 0}, Owned Spektum driver input to auto pilot
//{0, GPIO_8266_PD, 0}, Owned by the 8266 driver
//{0, GPIO_8266_RST, 0}, Owned by the 8266 driver
/* PX4FMU GPIOs ***********************************************************************************/
/* LEDs */
/* Port[CON-PIN] FMUv5 Delta */
#define GPIO_LED1 /* PB14[CN12-28] DRDY2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14)
#define GPIO_LED2 /* PB0[CN11-34] RSSI */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define GPIO_LED3 /* PB7[CN11-21] GPS1_TX */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN7)
#define GPIO_LED_RED GPIO_LED1
#define GPIO_LED_GREEN GPIO_LED2
#define GPIO_LED_BLUE GPIO_LED3
/* Define the Chip Selects */
#define GPIO_SPI_CS_MPU9250 /* PF2[CN11-52] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN2)
#define GPIO_SPI_CS_HMC5983 /* PF3[CN12-58] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN3)
#define GPIO_SPI_CS_LIS3MDL /* PF4[CN12-38] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN4)
#define GPIO_SPI_CS_FRAM /* PF5[CN12-36] */(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN5)
#define GPIO_SPI_CS_MS5611 /* PF10[CN12-42] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN10)
#define GPIO_SPI_CS_ICM_20608_G /* PF13[CN12-57] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN13)
/* Define the Ready interrupts */
#define GPIO_DRDY_MPU9250 /* PB4[CN12-27] */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN4)
#define GPIO_DRDY_HMC5983 /* PB15[CN12-26] */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN15)
#define GPIO_DRDY_ICM_20608_G /* PC5[CN12-6] */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN5)
/*
* Define the ability to shut off off the sensor signals
* by changing the signals to inputs
*/
#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz))
#define GPIO_SPI_CS_OFF_MPU9250 _PIN_OFF(GPIO_SPI_CS_MPU9250)
#define GPIO_SPI_CS_OFF_HMC5983 _PIN_OFF(GPIO_SPI_CS_HMC5983)
#define GPIO_SPI_CS_OFF_LIS3MDL _PIN_OFF(GPIO_SPI_CS_LIS3MDL)
#define GPIO_SPI_CS_OFF_MS5611 _PIN_OFF(GPIO_SPI_CS_MS5611)
#define GPIO_SPI_CS_OFF_ICM_20608_G _PIN_OFF(GPIO_SPI_CS_ICM_20608_G)
#define GPIO_DRDY_OFF_MPU9250 _PIN_OFF(GPIO_DRDY_MPU9250)
#define GPIO_DRDY_OFF_HMC5983 _PIN_OFF(GPIO_DRDY_HMC5983)
#define GPIO_DRDY_OFF_ICM_20608_G _PIN_OFF(GPIO_DRDY_ICM_20608_G)
/* 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)
/* SENSORS are on SPI1
* FRAM is on bus SPI4
* MS5611 is on bus SPI6
*/
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_RAMTRON 4
#define PX4_SPI_BUS_BARO 5
#define PX4_SPI_BUS_ICM 6
#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,0)
#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,1)
#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,2)
#define PX4_SPIDEV_HMC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,3)
#define PX4_SPIDEV_LIS PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,4)
#define PX4_SPIDEV_BMI PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,5)
#define PX4_SPIDEV_BMA PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,6)
#define PX4_SENSOR_BUS_CS_GPIO {0, 0, GPIO_SPI_CS_MPU9250, GPIO_SPI_CS_HMC5983, GPIO_SPI_CS_LIS3MDL, 0, 0}
#define PX4_SENSORS_BUS_FIRST_CS PX4_SPIDEV_GYRO
#define PX4_SENSORS_BUS_LAST_CS PX4_SPIDEV_BMA
#define PX4_SPIDEV_FRAM PX4_MK_SPI_SEL(PX4_SPI_BUS_RAMTRON,0)
#define PX4_RAMTRON_BUS_CS_GPIO {GPIO_SPI_CS_FRAM}
#define PX4_RAMTRON_BUS_FIRST_CS PX4_SPIDEV_FRAM
#define PX4_RAMTRON_BUS_LAST_CS PX4_SPIDEV_FRAM
#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_BARO,0)
#define PX4_BARO_BUS_CS_GPIO {GPIO_SPI_CS_MS5611}
#define PX4_BARO_BUS_FIRST_CS PX4_SPIDEV_BARO
#define PX4_BARO_BUS_LAST_CS PX4_SPIDEV_BARO
#define PX4_SPIDEV_ICM PX4_MK_SPI_SEL(PX4_SPI_BUS_ICM,0)
#define PX4_ICM_BUS_CS_GPIO {GPIO_SPI_CS_ICM_20608_G}
#define PX4_ICM_BUS_FIRST_CS PX4_SPIDEV_ICM
#define PX4_ICM_BUS_LAST_CS PX4_SPIDEV_ICM
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 4
#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION
/* Devices on the external bus.
*
* Note that these are unshifted addresses.
*/
#define PX4_I2C_OBDEV_LED 0x55
#define PX4_I2C_OBDEV_HMC5883 0x1e
#define PX4_I2C_OBDEV_LIS3MDL 0x1e
/*
* 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
*/
#define ADC_CHANNELS (1 << 0) | (1 << 1) | (1 << 2) | (1 << 3) | (1 << 4) | \
(1 << 8) | \
(1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14)
// ADC defines to be used in sensors.cpp to read from a particular channel
#define ADC_BATTERY_VOLTAGE_CHANNEL 0
#define ADC_BATTERY_CURRENT_CHANNEL 1
#define ADC_5V_RAIL_SENSE 10
#define ADC_RC_RSSI_CHANNEL 14
/* User GPIOs
*
* GPIO0-5 are the PWM servo outputs.
*/
#define GPIO_GPIO0_INPUT /* PE14[CN12-51] */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN14)
#define GPIO_GPIO1_INPUT /* PA10[CN12-33] */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
#define GPIO_GPIO2_INPUT /* PE11[CN12-56] */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
#define GPIO_GPIO3_INPUT /* PE9[CN12-52] */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN9)
#define GPIO_GPIO4_INPUT /* PD13[CN12-41] */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
#define GPIO_GPIO5_INPUT /* PD14[CN12-46] */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
#define GPIO_GPIO0_OUTPUT /* PE14[CN12-51] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14)
#define GPIO_GPIO1_OUTPUT /* PE13[CN12-55] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13)
#define GPIO_GPIO2_OUTPUT /* PE11[CN12-56] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11)
#define GPIO_GPIO3_OUTPUT /* PE9[CN12-52] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9)
#define GPIO_GPIO4_OUTPUT /* PD13[CN12-41] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
#define GPIO_GPIO5_OUTPUT /* PD14[CN12-46] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
/* Power supply control and monitoring GPIOs */
#define GPIO_VDD_BRICK_VALID /* PB10[CN12-25] */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN10)
#define GPIO_VDD_3V3_SENSORS_EN /* PE3[CN11-47] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
/* Tone alarm output */
#define TONE_ALARM_TIMER 2 /* timer 2 */
#define TONE_ALARM_CHANNEL /* PA5[CN12-11] TIM2_CH1 */ 1 /* channel 1 */
#define GPIO_TONE_ALARM_IDLE /* PA5[CN12-11] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN5)
#define GPIO_TONE_ALARM /* PA5[CN12-11] */ (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN5)
/* PWM
*
* Six PWM outputs are configured.
*
* Pins:
*
* CH1 : PE14 : TIM1_CH4
* CH2 : PE13 : TIM1_CH3
* CH3 : PE11 : TIM1_CH2
* CH4 : PE9 : TIM1_CH1
* CH5 : PD13 : TIM4_CH2
* CH6 : PD14 : TIM4_CH3
*/
#define GPIO_TIM1_CH1OUT /* PE14[CN12-51] */ (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN9)
#define GPIO_TIM1_CH2OUT /* PE13[CN12-55] */ (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11)
#define GPIO_TIM1_CH3OUT /* PE11[CN12-56] */ (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13)
#define GPIO_TIM1_CH4OUT /* PE9[CN12-52] */ (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14)
#define GPIO_TIM4_CH2OUT /* PD13[CN12-41] */ (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN13)
#define GPIO_TIM4_CH3OUT /* PD14[CN12-46] */ (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN14)
#define DIRECT_PWM_OUTPUT_CHANNELS 6
#define GPIO_TIM1_CH1IN /* PE14[CN12-51] */ GPIO_TIM1_CH1IN_2
#define GPIO_TIM1_CH2IN /* PE13[CN12-55] */ GPIO_TIM1_CH2IN_2
#define GPIO_TIM1_CH3IN /* PE11[CN12-56] */ GPIO_TIM1_CH3IN_2
#define GPIO_TIM1_CH4IN /* PE9[CN12-52] */ GPIO_TIM1_CH4IN_2
#define GPIO_TIM4_CH2IN /* PD13[CN12-41] */ GPIO_TIM4_CH2IN_2
#define GPIO_TIM4_CH3IN /* PD14[CN12-46] */ GPIO_TIM4_CH3IN_2
#define DIRECT_INPUT_TIMER_CHANNELS 6
/* USB OTG FS
*
* PA9 OTG_FS_VBUS VBUS sensing
*/
#define GPIO_OTGFS_VBUS /* PA9[CN12-21] */ (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|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 /* PA7[CN12-15] */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* PB0[CN11-34] */ GPIO_TIM3_CH3IN_1
#define RC_SERIAL_PORT "/dev/ttyS4"
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
#define PWMIN_TIMER 4
#define PWMIN_TIMER_CHANNEL /* PD13[CN12-41] */ 2
#define GPIO_PWM_IN /* PD13[CN12-41] */ GPIO_TIM4_CH2IN_2
#define GPIO_RSSI_IN /* PC4[CN12-34] */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
#define GPIO_LED_SAFETY /* PE12[CN12-49] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN12)
#define GPIO_BTN_SAFETY /* PE10[CN12-47] */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN10)
#define GPIO_PERIPH_3V3_EN /* PG4[CN12-69] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4)
#define GPIO_SBUS_INV /* PD10[CN12-65] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
#define INVERT_RC_INPUT(_s) px4_arch_gpiowrite(GPIO_SBUS_INV, _s);
#define GPIO_8266_GPIO0 /* PD15[CN12-48] */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN15)
#define GPIO_SPEKTRUM_PWR_EN /* PE4[CN11-48] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
#define GPIO_8266_PD /* PE7[CN12-44] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN7)
#define GPIO_8266_RST /* PG10[CN11-66] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10)
#define GPIO_VDD_5V_PERIPH_OC /* PE15[CN12-53] */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN15)
/* Power switch controls ******************************************************/
#define POWER_SPEKTRUM(_s) px4_arch_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (1-_s))
#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(GPIO_USART1_RX)
// FMUv4 has a separate GPIO for serial RC output
#define GPIO_RC_OUT /* PE5[CN11-50] */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5)
#define SPEKTRUM_RX_AS_GPIO() px4_arch_configgpio(GPIO_RC_OUT)
#define SPEKTRUM_RX_HIGH(_s) px4_arch_gpiowrite(GPIO_RC_OUT, (_s))
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
/* SD card bringup does not work if performed on the IDLE thread because it
* will cause waiting. Use either:
*
* CONFIG_LIB_BOARDCTL=y, OR
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
*/
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \
!defined(CONFIG_BOARD_INITTHREAD)
# warning SDIO initialization cannot be perfomed on the IDLE thread
#endif
#define BOARD_NAME "PX4NUCLEOF767ZI_V1"
/* 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_BRICK_VALID (px4_arch_gpioread(GPIO_VDD_BRICK_VALID))
#define BOARD_ADC_SERVO_VALID (1)
#define BOARD_ADC_PERIPH_5V_OC (px4_arch_gpioread(GPIO_VDD_5V_PERIPH_OC))
#define BOARD_ADC_HIPOWER_5V_OC (0)
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
#define BOARD_FMU_GPIO_TAB { \
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, \
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, \
{GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, 0}, \
{GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0}, \
{GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0}, \
{GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0}, \
{0, GPIO_VDD_3V3_SENSORS_EN, 0}, \
{GPIO_VDD_BRICK_VALID, 0, 0}, }
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/****************************************************************************************************
* 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);
/************************************************************************************
* Name: stm32_spi_bus_initialize
*
* Description:
* Called to configure SPI Buses.
*
************************************************************************************/
extern int stm32_spi_bus_initialize(void);
/****************************************************************************************************
* Name: board_spi_reset board_peripheral_reset
*
* Description:
* Called to reset SPI and the perferal bus
*
****************************************************************************************************/
void board_spi_reset(int ms);
extern void board_peripheral_reset(int ms);
/****************************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to configure USB IO.
*
****************************************************************************************************/
extern void stm32_usbinitialize(void);
#include "../common/board_common.h"
#endif /* __ASSEMBLY__ */
__END_DECLS

View File

@ -0,0 +1,129 @@
/****************************************************************************
*
* 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 px4nucleo_can.c
*
* Board-specific CAN functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_config.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/can.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_arch.h"
#include "chip.h"
#include "stm32_can.h"
#include "board_config.h"
#ifdef CONFIG_CAN
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration ********************************************************************/
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
# undef CONFIG_STM32_CAN2
#endif
#ifdef CONFIG_STM32_CAN1
# define CAN_PORT 1
#else
# define CAN_PORT 2
#endif
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* 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

View File

@ -0,0 +1,593 @@
/****************************************************************************
*
* Copyright (c) 2012-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 px4nucleo_init.c
*
* PX4FMU-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialization.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_config.h>
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/arch.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 "board_config.h"
#include <stm32_uart.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_led.h>
#include <systemlib/px4_macros.h>
#include <systemlib/cpuload.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
#include <systemlib/hardfault_log.h>
#include <systemlib/systemlib.h>
#include "up_internal.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Debug ********************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# define message(...) syslog(__VA_ARGS__)
# else
# define message(...) printf(__VA_ARGS__)
# endif
#else
# ifdef CONFIG_DEBUG
# define message syslog
# else
# define message printf
# endif
#endif
/*
* 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
/****************************************************************************
* Protected Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* Name: board_peripheral_reset
*
* Description:
*
************************************************************************************/
__EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
stm32_configgpio(GPIO_PERIPH_3V3_EN);
stm32_gpiowrite(GPIO_PERIPH_3V3_EN, 0);
bool last = stm32_gpioread(GPIO_SPEKTRUM_PWR_EN);
/* Keep Spektum on to discharge rail*/
stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, 1);
/* wait for the peripheral rail to reach GND */
usleep(ms * 1000);
warnx("reset done, %d ms", ms);
/* re-enable power */
/* switch the peripheral rail back on */
stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, last);
stm32_gpiowrite(GPIO_PERIPH_3V3_EN, 1);
}
/************************************************************************************
* 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)
{
/* configure LEDs */
board_autoled_initialize();
/* configure ADC pins */
stm32_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */
stm32_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */
stm32_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */
stm32_configgpio(GPIO_ADC1_IN11); /* RSSI analog in */
/* configure power supply control/sense pins */
stm32_configgpio(GPIO_PERIPH_3V3_EN);
stm32_configgpio(GPIO_VDD_BRICK_VALID);
stm32_configgpio(GPIO_SBUS_INV);
stm32_configgpio(GPIO_8266_GPIO0);
stm32_configgpio(GPIO_SPEKTRUM_PWR_EN);
stm32_configgpio(GPIO_8266_PD);
stm32_configgpio(GPIO_8266_RST);
stm32_configgpio(GPIO_BTN_SAFETY);
#ifdef GPIO_RC_OUT
stm32_configgpio(GPIO_RC_OUT); /* Serial RC output pin */
stm32_gpiowrite(GPIO_RC_OUT, 1); /* set it high to pull RC input up */
#endif
/* configure the GPIO pins to outputs and keep them low */
stm32_configgpio(GPIO_GPIO0_OUTPUT);
stm32_configgpio(GPIO_GPIO1_OUTPUT);
stm32_configgpio(GPIO_GPIO2_OUTPUT);
stm32_configgpio(GPIO_GPIO3_OUTPUT);
stm32_configgpio(GPIO_GPIO4_OUTPUT);
stm32_configgpio(GPIO_GPIO5_OUTPUT);
/* configure SPI interfaces */
stm32_spiinitialize();
}
/****************************************************************************
* 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)
{
#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
/* run C++ ctors before we go any further */
up_cxxinitialize();
# if defined(CONFIG_EXAMPLES_NSH_CXXINITIALIZE)
# error CONFIG_EXAMPLES_NSH_CXXINITIALIZE Must not be defined! Use CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE.
# endif
#else
# error platform is dependent on c++ both CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE must be defined.
#endif
/* configure the high-resolution time/callout interface */
hrt_init();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
message("DMA alloc FAILED");
}
/* configure CPU load estimation */
#ifdef CONFIG_SCHED_INSTRUMENTATION
cpuload_initialize_once();
#endif
/* 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);
#if defined(CONFIG_STM32_BBSRAM)
/* NB. the use of the console requires the hrt running
* to poll the DMA
*/
/* Using Battery Backed Up SRAM */
int filesizes[CONFIG_STM32_BBSRAM_FILES + 1] = BSRAM_FILE_SIZES;
stm32_bbsraminitialize(BBSRAM_PATH, filesizes);
#if defined(CONFIG_STM32_SAVE_CRASHDUMP)
/* Panic Logging in Battery Backed Up Files */
/*
* In an ideal world, if a fault happens in flight the
* system save it to BBSRAM will then reboot. Upon
* rebooting, the system will log the fault to disk, recover
* the flight state and continue to fly. But if there is
* a fault on the bench or in the air that prohibit the recovery
* or committing the log to disk, the things are too broken to
* fly. So the question is:
*
* Did we have a hard fault and not make it far enough
* through the boot sequence to commit the fault data to
* the SD card?
*/
/* Do we have an uncommitted hard fault in BBSRAM?
* - this will be reset after a successful commit to SD
*/
int hadCrash = hardfault_check_status("boot");
if (hadCrash == OK) {
message("[boot] There is a hard fault logged. Hold down the SPACE BAR," \
" while booting to halt the system!\n");
/* Yes. So add one to the boot count - this will be reset after a successful
* commit to SD
*/
int reboots = hardfault_increment_reboot("boot", false);
/* Also end the misery for a user that holds for a key down on the console */
int bytesWaiting;
ioctl(fileno(stdin), FIONREAD, (unsigned long)((uintptr_t) &bytesWaiting));
if (reboots > 2 || bytesWaiting != 0) {
/* Since we can not commit the fault dump to disk. Display it
* to the console.
*/
hardfault_write("boot", fileno(stdout), HARDFAULT_DISPLAY_FORMAT, false);
message("[boot] There were %d reboots with Hard fault that were not committed to disk - System halted %s\n",
reboots,
(bytesWaiting == 0 ? "" : " Due to Key Press\n"));
/* For those of you with a debugger set a break point on up_assert and
* then set dbgContinue = 1 and go.
*/
/* Clear any key press that got us here */
static volatile bool dbgContinue = false;
int c = '>';
while (!dbgContinue) {
switch (c) {
case EOF:
case '\n':
case '\r':
case ' ':
continue;
default:
putchar(c);
putchar('\n');
switch (c) {
case 'D':
case 'd':
hardfault_write("boot", fileno(stdout), HARDFAULT_DISPLAY_FORMAT, false);
break;
case 'C':
case 'c':
hardfault_rearm("boot");
hardfault_increment_reboot("boot", true);
break;
case 'B':
case 'b':
dbgContinue = true;
break;
default:
break;
} // Inner Switch
message("\nEnter B - Continue booting\n" \
"Enter C - Clear the fault log\n" \
"Enter D - Dump fault log\n\n?>");
fflush(stdout);
if (!dbgContinue) {
c = getchar();
}
break;
} // outer switch
} // for
} // inner if
} // outer if
#endif // CONFIG_STM32_SAVE_CRASHDUMP
#endif // CONFIG_STM32_BBSRAM
/* initial LED state */
drv_led_start();
led_off(LED_RED);
led_off(LED_GREEN);
led_off(LED_BLUE);
#ifdef CONFIG_SPI
int ret = stm32_spi_bus_initialize();
if (ret != OK) {
board_autoled_on(LED_RED);
return ret;
}
#endif
#ifdef CONFIG_MMCSD
ret = stm32_sdio_initialize();
if (ret != OK) {
board_autoled_on(LED_RED);
return ret;
}
#endif
return OK;
}
static void copy_reverse(stack_word_t *dest, stack_word_t *src, int size)
{
while (size--) {
*dest++ = *src--;
}
}
__EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const uint8_t *filename, int lineno)
{
/* We need a chunk of ram to save the complete context in.
* Since we are going to reboot we will use &_sdata
* which is the lowest memory and the amount we will save
* _should be_ below any resources we need herein.
* Unfortunately this is hard to test. See dead below
*/
fullcontext_s *pdump = (fullcontext_s *)&_sdata;
(void)enter_critical_section();
struct tcb_s *rtcb = (struct tcb_s *)tcb;
/* Zero out everything */
memset(pdump, 0, sizeof(fullcontext_s));
/* Save Info */
pdump->info.lineno = lineno;
if (filename) {
int offset = 0;
unsigned int len = strlen((char *)filename) + 1;
if (len > sizeof(pdump->info.filename)) {
offset = len - sizeof(pdump->info.filename) ;
}
strncpy(pdump->info.filename, (char *)&filename[offset], sizeof(pdump->info.filename));
}
/* Save the value of the pointer for current_regs as debugging info.
* It should be NULL in case of an ASSERT and will aid in cross
* checking the validity of system memory at the time of the
* fault.
*/
pdump->info.current_regs = (uintptr_t) CURRENT_REGS;
/* Save Context */
#if CONFIG_TASK_NAME_SIZE > 0
strncpy(pdump->info.name, rtcb->name, CONFIG_TASK_NAME_SIZE);
#endif
pdump->info.pid = rtcb->pid;
/* If current_regs is not NULL then we are in an interrupt context
* and the user context is in current_regs else we are running in
* the users context
*/
if (CURRENT_REGS) {
pdump->info.stacks.interrupt.sp = currentsp;
pdump->info.flags |= (eRegsPresent | eUserStackPresent | eIntStackPresent);
memcpy(pdump->info.regs, (void *)CURRENT_REGS, sizeof(pdump->info.regs));
pdump->info.stacks.user.sp = pdump->info.regs[REG_R13];
} else {
/* users context */
pdump->info.flags |= eUserStackPresent;
pdump->info.stacks.user.sp = currentsp;
}
if (pdump->info.pid == 0) {
pdump->info.stacks.user.top = g_idle_topstack - 4;
pdump->info.stacks.user.size = CONFIG_IDLETHREAD_STACKSIZE;
} else {
pdump->info.stacks.user.top = (uint32_t) rtcb->adj_stack_ptr;
pdump->info.stacks.user.size = (uint32_t) rtcb->adj_stack_size;;
}
#if CONFIG_ARCH_INTERRUPTSTACK > 3
/* Get the limits on the interrupt stack memory */
pdump->info.stacks.interrupt.top = (uint32_t)&g_intstackbase;
pdump->info.stacks.interrupt.size = (CONFIG_ARCH_INTERRUPTSTACK & ~3);
/* If In interrupt Context save the interrupt stack data centered
* about the interrupt stack pointer
*/
if ((pdump->info.flags & eIntStackPresent) != 0) {
stack_word_t *ps = (stack_word_t *) pdump->info.stacks.interrupt.sp;
copy_reverse(pdump->istack, &ps[arraySize(pdump->istack) / 2], arraySize(pdump->istack));
}
/* Is it Invalid? */
if (!(pdump->info.stacks.interrupt.sp <= pdump->info.stacks.interrupt.top &&
pdump->info.stacks.interrupt.sp > pdump->info.stacks.interrupt.top - pdump->info.stacks.interrupt.size)) {
pdump->info.flags |= eInvalidIntStackPrt;
}
#endif
/* If In interrupt context or User save the user stack data centered
* about the user stack pointer
*/
if ((pdump->info.flags & eUserStackPresent) != 0) {
stack_word_t *ps = (stack_word_t *) pdump->info.stacks.user.sp;
copy_reverse(pdump->ustack, &ps[arraySize(pdump->ustack) / 2], arraySize(pdump->ustack));
}
/* Is it Invalid? */
if (!(pdump->info.stacks.user.sp <= pdump->info.stacks.user.top &&
pdump->info.stacks.user.sp > pdump->info.stacks.user.top - pdump->info.stacks.user.size)) {
pdump->info.flags |= eInvalidUserStackPtr;
}
int rv = stm32_bbsram_savepanic(HARDFAULT_FILENO, (uint8_t *)pdump, sizeof(fullcontext_s));
/* Test if memory got wiped because of using _sdata */
if (rv == -ENXIO) {
char *dead = "Memory wiped - dump not saved!";
while (*dead) {
up_lowputc(*dead++);
}
} else if (rv == -ENOSPC) {
/* hard fault again */
up_lowputc('!');
}
#if defined(CONFIG_BOARD_RESET_ON_CRASH)
px4_systemreset(false);
#endif
}

View File

@ -0,0 +1,229 @@
/****************************************************************************
*
* 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_LED_GREEN, // Indexed by BOARD_LED_GREEN
GPIO_LED_BLUE, // Indexed by BOARD_LED_BLUE
GPIO_LED_RED, // Indexed by BOARD_LED_RED
GPIO_LED_SAFETY, // Indexed by LED_SAFETY by xlatpx4
};
#else
# define xlat(p)
static uint32_t g_ledmap[] = {
GPIO_LED_BLUE, // Indexed by LED_BLUE
GPIO_LED_RED, // Indexed by LED_RED, LED_AMBER
GPIO_LED_SAFETY, // Indexed by LED_SAFETY
GPIO_LED_GREEN, // Indexed by LED_GREEN
};
#endif
__EXPORT void led_init(void)
{
/* Configure LED GPIOs for output */
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 High to switch on */
stm32_gpiowrite(g_ledmap[led], state);
}
static bool phy_get_led(int led)
{
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,193 @@
/****************************************************************************
*
* 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 <px4_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
****************************************************************************/
/* Configuration ************************************************************/
/* Debug ********************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# define message(...) syslog(__VA_ARGS__)
# else
# define message(...) printf(__VA_ARGS__)
# endif
#else
# ifdef CONFIG_DEBUG
# define message syslog
# else
# define message printf
# endif
#endif
/* 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) {
message("[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) {
message("[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,412 @@
/****************************************************************************
*
* 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 px4nucleo_spi.c
*
* Board-specific SPI functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_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"
#include <systemlib/err.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Debug ********************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# define message(...) syslog(__VA_ARGS__)
# else
# define message(...) printf(__VA_ARGS__)
# endif
#else
# ifdef CONFIG_DEBUG
# define message syslog
# else
# define message printf
# endif
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
*
************************************************************************************/
__EXPORT void stm32_spiinitialize(void)
{
#ifdef CONFIG_STM32F7_SPI1
stm32_configgpio(GPIO_SPI_CS_MPU9250);
stm32_configgpio(GPIO_SPI_CS_HMC5983);
stm32_configgpio(GPIO_SPI_CS_MS5611);
stm32_configgpio(GPIO_SPI_CS_ICM_20608_G);
/* De-activate all peripherals,
* required for some peripheral
* state machines
*/
stm32_gpiowrite(GPIO_SPI_CS_MPU9250, 1);
stm32_gpiowrite(GPIO_SPI_CS_HMC5983, 1);
stm32_gpiowrite(GPIO_SPI_CS_MS5611, 1);
stm32_gpiowrite(GPIO_SPI_CS_ICM_20608_G, 1);
stm32_configgpio(GPIO_DRDY_MPU9250);
stm32_configgpio(GPIO_DRDY_HMC5983);
stm32_configgpio(GPIO_DRDY_ICM_20608_G);
#endif
#ifdef CONFIG_STM32F7_SPI2
stm32_configgpio(GPIO_SPI_CS_FRAM);
stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
#endif
}
/************************************************************************************
* Name: stm32_spi_bus_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
*
************************************************************************************/
static struct spi_dev_s *spi_sensors;
static struct spi_dev_s *spi_fram;
static struct spi_dev_s *spi_baro;
static struct spi_dev_s *spi_icm;
__EXPORT int stm32_spi_bus_initialize(void)
{
/* Configure SPI-based devices */
spi_sensors = stm32_spibus_initialize(PX4_SPI_BUS_SENSORS);
if (!spi_sensors) {
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
return -ENODEV;
}
/* Default PX4_SPI_BUS_SENSORS to 1MHz and de-assert the known chip selects. */
SPI_SETFREQUENCY(spi_sensors, 10000000);
SPI_SETBITS(spi_sensors, 8);
SPI_SETMODE(spi_sensors, SPIDEV_MODE3);
for (int cs = PX4_SENSORS_BUS_FIRST_CS; cs <= PX4_SENSORS_BUS_LAST_CS; cs++) {
SPI_SELECT(spi_sensors, cs, false);
}
/* Get the SPI port for the FRAM */
spi_fram = stm32_spibus_initialize(PX4_SPI_BUS_RAMTRON);
if (!spi_fram) {
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON);
return -ENODEV;
}
/* Default SPI_BUS_RAMTRON to 12MHz and de-assert the known chip selects.
*/
SPI_SETFREQUENCY(spi_fram, 12 * 1000 * 1000);
SPI_SETBITS(spi_fram, 8);
SPI_SETMODE(spi_fram, SPIDEV_MODE3);
for (int cs = PX4_RAMTRON_BUS_FIRST_CS; cs <= PX4_RAMTRON_BUS_LAST_CS; cs++) {
SPI_SELECT(spi_fram, cs, false);
}
/* Get the SPI port for the BARO */
spi_baro = stm32_spibus_initialize(PX4_SPI_BUS_BARO);
if (!spi_baro) {
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_BARO);
return -ENODEV;
}
/* MS5611 has max SPI clock speed of 20MHz
*/
SPI_SETFREQUENCY(spi_baro, 20 * 1000 * 1000);
SPI_SETBITS(spi_baro, 8);
SPI_SETMODE(spi_baro, SPIDEV_MODE3);
for (int cs = PX4_BARO_BUS_FIRST_CS; cs <= PX4_BARO_BUS_LAST_CS; cs++) {
SPI_SELECT(spi_baro, cs, false);
}
/* Get the SPI port for the PX4_SPI_BUS_ICM */
spi_icm = stm32_spibus_initialize(PX4_SPI_BUS_ICM);
if (!spi_icm) {
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_ICM);
return -ENODEV;
}
/* ICM 20608 G has max SPI clock speed of 8MHz
*/
SPI_SETFREQUENCY(spi_icm, 8 * 1000 * 1000);
SPI_SETBITS(spi_icm, 8);
SPI_SETMODE(spi_icm, SPIDEV_MODE3);
for (int cs = PX4_ICM_BUS_FIRST_CS; cs <= PX4_ICM_BUS_LAST_CS; cs++) {
SPI_SELECT(spi_icm, cs, false);
}
return OK;
}
/* Define CS GPIO array */
static const uint32_t spi1selects_gpio[] = PX4_SENSOR_BUS_CS_GPIO;
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
/* SPI select is active low, so write !selected to select the device */
int sel = (int) devid;
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_SENSORS);
/* Making sure the other peripherals are not selected */
for (int cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
if (spi1selects_gpio[cs] != 0) {
stm32_gpiowrite(spi1selects_gpio[cs], 1);
}
}
uint32_t gpio = spi1selects_gpio[PX4_SPI_DEV_ID(sel)];
if (gpio) {
stm32_gpiowrite(gpio, !selected);
}
}
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
return SPI_STATUS_PRESENT;
}
/* Define CS GPIO array */
static const uint32_t spi4selects_gpio[] = PX4_RAMTRON_BUS_CS_GPIO;
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
int sel = (int) devid;
if (devid == SPIDEV_FLASH) {
sel = PX4_SPIDEV_FRAM;
}
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_RAMTRON);
/* Making sure the other peripherals are not selected */
for (int cs = 0; arraySize(spi4selects_gpio) > 1 && cs < arraySize(spi4selects_gpio); cs++) {
stm32_gpiowrite(spi4selects_gpio[cs], 1);
}
uint32_t gpio = spi4selects_gpio[PX4_SPI_DEV_ID(sel)];
if (gpio) {
stm32_gpiowrite(gpio, !selected);
}
}
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
/* FRAM is always present */
return SPI_STATUS_PRESENT;
}
static const uint32_t spi5selects_gpio[] = PX4_BARO_BUS_CS_GPIO;
__EXPORT void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
/* SPI select is active low, so write !selected to select the device */
int sel = (int) devid;
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_BARO);
/* Making sure the other peripherals are not selected */
for (int cs = 0; arraySize(spi5selects_gpio) > 1 && cs < arraySize(spi5selects_gpio); cs++) {
stm32_gpiowrite(spi5selects_gpio[cs], 1);
}
uint32_t gpio = spi5selects_gpio[PX4_SPI_DEV_ID(sel)];
if (gpio) {
stm32_gpiowrite(gpio, !selected);
}
}
__EXPORT uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
/* FRAM is always present */
return SPI_STATUS_PRESENT;
}
static const uint32_t spi6selects_gpio[] = PX4_ICM_BUS_CS_GPIO;
__EXPORT void stm32_spi6select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
/* SPI select is active low, so write !selected to select the device */
int sel = (int) devid;
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_ICM);
/* Making sure the other peripherals are not selected */
for (int cs = 0; arraySize(spi6selects_gpio) > 1 && cs < arraySize(spi6selects_gpio); cs++) {
stm32_gpiowrite(spi6selects_gpio[cs], 1);
}
uint32_t gpio = spi6selects_gpio[PX4_SPI_DEV_ID(sel)];
if (gpio) {
stm32_gpiowrite(gpio, !selected);
}
}
__EXPORT uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
/* FRAM is always present */
return SPI_STATUS_PRESENT;
}
__EXPORT void board_spi_reset(int ms)
{
/* disable SPI bus */
stm32_configgpio(GPIO_SPI_CS_OFF_MPU9250);
stm32_configgpio(GPIO_SPI_CS_OFF_HMC5983);
stm32_configgpio(GPIO_SPI_CS_OFF_MS5611);
stm32_configgpio(GPIO_SPI_CS_OFF_ICM_20608_G);
stm32_gpiowrite(GPIO_SPI_CS_OFF_MPU9250, 0);
stm32_gpiowrite(GPIO_SPI_CS_OFF_HMC5983, 0);
stm32_gpiowrite(GPIO_SPI_CS_OFF_MS5611, 0);
stm32_gpiowrite(GPIO_SPI_CS_OFF_ICM_20608_G, 0);
stm32_configgpio(GPIO_SPI1_SCK_OFF);
stm32_configgpio(GPIO_SPI1_MISO_OFF);
stm32_configgpio(GPIO_SPI1_MOSI_OFF);
stm32_gpiowrite(GPIO_SPI1_SCK_OFF, 0);
stm32_gpiowrite(GPIO_SPI1_MISO_OFF, 0);
stm32_gpiowrite(GPIO_SPI1_MOSI_OFF, 0);
stm32_configgpio(GPIO_DRDY_OFF_MPU9250);
stm32_configgpio(GPIO_DRDY_OFF_HMC5983);
stm32_configgpio(GPIO_DRDY_OFF_ICM_20608_G);
stm32_gpiowrite(GPIO_DRDY_OFF_MPU9250, 0);
stm32_gpiowrite(GPIO_DRDY_OFF_HMC5983, 0);
stm32_gpiowrite(GPIO_DRDY_OFF_ICM_20608_G, 0);
/* set the sensor rail off */
stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0);
/* wait for the sensor rail to reach GND */
usleep(ms * 1000);
warnx("reset done, %d ms", ms);
/* re-enable power */
/* switch the sensor rail back on */
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1);
/* wait a bit before starting SPI, different times didn't influence results */
usleep(100);
/* reconfigure the SPI pins */
#ifdef CONFIG_STM32F7_SPI1
stm32_configgpio(GPIO_SPI_CS_MPU9250);
stm32_configgpio(GPIO_SPI_CS_HMC5983);
stm32_configgpio(GPIO_SPI_CS_MS5611);
stm32_configgpio(GPIO_SPI_CS_ICM_20608_G);
/* De-activate all peripherals,
* required for some peripheral
* state machines
*/
stm32_gpiowrite(GPIO_SPI_CS_MPU9250, 1);
stm32_gpiowrite(GPIO_SPI_CS_HMC5983, 1);
stm32_gpiowrite(GPIO_SPI_CS_MS5611, 1);
stm32_gpiowrite(GPIO_SPI_CS_ICM_20608_G, 1);
stm32_configgpio(GPIO_SPI1_SCK);
stm32_configgpio(GPIO_SPI1_MISO);
stm32_configgpio(GPIO_SPI1_MOSI);
// // XXX bring up the EXTI pins again
// stm32_configgpio(GPIO_GYRO_DRDY);
// stm32_configgpio(GPIO_MAG_DRDY);
// stm32_configgpio(GPIO_ACCEL_DRDY);
// stm32_configgpio(GPIO_EXTI_MPU_DRDY);
#endif
}

View File

@ -0,0 +1,126 @@
/****************************************************************************
*
* 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 px4nucleo_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"
__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,
}
};
__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
}
};

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 px4nucleo_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);
}