From 925102464bd2508a6a6f6f5a83fcec22da99ed22 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 12 Dec 2016 12:11:25 -1000 Subject: [PATCH] Adding px4fmu-v4pro --- Images/px4fmu-v4pro.prototype | 12 + ROMFS/px4fmu_common/init.d/rc.sensors | 23 + .../configs/nuttx_px4fmu-v4pro_default.cmake | 225 +++ nuttx-configs/px4fmu-v4pro/Kconfig | 22 + nuttx-configs/px4fmu-v4pro/include/board.h | 433 +++++ .../px4fmu-v4pro/include/nsh_romfsimg.h | 42 + nuttx-configs/px4fmu-v4pro/nsh/Make.defs | 164 ++ nuttx-configs/px4fmu-v4pro/nsh/defconfig | 1556 +++++++++++++++++ nuttx-configs/px4fmu-v4pro/nsh/setenv.sh | 67 + nuttx-configs/px4fmu-v4pro/scripts/ld.script | 158 ++ nuttx-configs/px4fmu-v4pro/src/Makefile | 88 + nuttx-configs/px4fmu-v4pro/src/empty.c | 4 + .../boards/px4fmu-v4pro/CMakeLists.txt | 48 + .../boards/px4fmu-v4pro/board_config.h | 388 ++++ src/drivers/boards/px4fmu-v4pro/px4fmu_can.c | 130 ++ src/drivers/boards/px4fmu-v4pro/px4fmu_init.c | 674 +++++++ src/drivers/boards/px4fmu-v4pro/px4fmu_led.c | 106 ++ src/drivers/boards/px4fmu-v4pro/px4fmu_spi.c | 263 +++ .../boards/px4fmu-v4pro/px4fmu_timer_config.c | 126 ++ src/drivers/boards/px4fmu-v4pro/px4fmu_usb.c | 107 ++ 20 files changed, 4636 insertions(+) create mode 100644 Images/px4fmu-v4pro.prototype create mode 100644 cmake/configs/nuttx_px4fmu-v4pro_default.cmake create mode 100644 nuttx-configs/px4fmu-v4pro/Kconfig create mode 100644 nuttx-configs/px4fmu-v4pro/include/board.h create mode 100644 nuttx-configs/px4fmu-v4pro/include/nsh_romfsimg.h create mode 100644 nuttx-configs/px4fmu-v4pro/nsh/Make.defs create mode 100644 nuttx-configs/px4fmu-v4pro/nsh/defconfig create mode 100644 nuttx-configs/px4fmu-v4pro/nsh/setenv.sh create mode 100644 nuttx-configs/px4fmu-v4pro/scripts/ld.script create mode 100644 nuttx-configs/px4fmu-v4pro/src/Makefile create mode 100644 nuttx-configs/px4fmu-v4pro/src/empty.c create mode 100644 src/drivers/boards/px4fmu-v4pro/CMakeLists.txt create mode 100644 src/drivers/boards/px4fmu-v4pro/board_config.h create mode 100644 src/drivers/boards/px4fmu-v4pro/px4fmu_can.c create mode 100644 src/drivers/boards/px4fmu-v4pro/px4fmu_init.c create mode 100644 src/drivers/boards/px4fmu-v4pro/px4fmu_led.c create mode 100644 src/drivers/boards/px4fmu-v4pro/px4fmu_spi.c create mode 100644 src/drivers/boards/px4fmu-v4pro/px4fmu_timer_config.c create mode 100644 src/drivers/boards/px4fmu-v4pro/px4fmu_usb.c diff --git a/Images/px4fmu-v4pro.prototype b/Images/px4fmu-v4pro.prototype new file mode 100644 index 0000000000..9333ff619c --- /dev/null +++ b/Images/px4fmu-v4pro.prototype @@ -0,0 +1,12 @@ +{ + "board_id": 13, + "magic": "PX4FWv1", + "description": "Firmware for the PX4FMUv4PRO board, based on STM32F469", + "image": "", + "build_time": 0, + "summary": "PX4FMUv4PRO", + "version": "0.1", + "image_size": 0, + "git_identity": "", + "board_revision": 0 +} diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index ac7093341c..7e1c53cf23 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -299,6 +299,29 @@ then fi fi +if ver hwcmp PX4FMU_V4PRO +then + # Internal SPI bus ICM-20608-G + if mpu6000 -R 2 -T 20608 start + then + fi + + # Internal SPI bus mpu9250 + if mpu9250 -R 2 start + then + fi + + # Possible external compasses + if hmc5883 -X start + then + fi + + # Internal SPI bus + if lis3mdl -R 2 start + then + fi +fi + if meas_airspeed start then else diff --git a/cmake/configs/nuttx_px4fmu-v4pro_default.cmake b/cmake/configs/nuttx_px4fmu-v4pro_default.cmake new file mode 100644 index 0000000000..e8d68ff3b7 --- /dev/null +++ b/cmake/configs/nuttx_px4fmu-v4pro_default.cmake @@ -0,0 +1,225 @@ +include(nuttx/px4_impl_nuttx) + +px4_nuttx_configure(HWCLASS m4 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/px4io + drivers/boards/px4fmu-v4pro + drivers/rgbled + drivers/mpu6000 + drivers/mpu9250 + drivers/lsm303d + drivers/l3gd20 + 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/vmount + drivers/pwm_input + drivers/camera_trigger + drivers/bst + drivers/snapdragon_rc_pwm + drivers/lis3mdl + drivers/sf1xx + 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 + + # + # Testing + # + drivers/sf0x/sf0x_tests + drivers/test_ppm + modules/commander/commander_tests + modules/mc_pos_control/mc_pos_control_tests + modules/controllib_test + modules/mavlink/mavlink_tests + modules/unit_test + modules/uORB/uORB_tests + systemcmds/tests + + # + # General system control + # + modules/commander + modules/load_mon + modules/navigator + modules/mavlink + modules/gpio_led + modules/uavcan + modules/land_detector + + # + # Estimation modules (EKF/ SO3 / other filters) + # + 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/sdlog2 + modules/logger + + # + # Library modules + # + modules/param + modules/systemlib + modules/systemlib/mixer + modules/uORB + modules/dataman + + # + # Libraries + # + lib/controllib + lib/mathlib + lib/mathlib/math/filter + 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 + + # EKF + examples/ekf_att_pos_estimator +) + +set(config_extra_builtin_cmds + serdis + sercon + ) + +set(config_io_board + px4io-v2 + ) + +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" + COMPILE_FLAGS "-Os") + +add_custom_target(serdis) +set_target_properties(serdis PROPERTIES + PRIORITY "SCHED_PRIORITY_DEFAULT" + MAIN "serdis" + STACK_MAIN "2048" + COMPILE_FLAGS "-Os") diff --git a/nuttx-configs/px4fmu-v4pro/Kconfig b/nuttx-configs/px4fmu-v4pro/Kconfig new file mode 100644 index 0000000000..9af3690362 --- /dev/null +++ b/nuttx-configs/px4fmu-v4pro/Kconfig @@ -0,0 +1,22 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +if ARCH_BOARD_PX4FMU_V4PRO + +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 diff --git a/nuttx-configs/px4fmu-v4pro/include/board.h b/nuttx-configs/px4fmu-v4pro/include/board.h new file mode 100644 index 0000000000..9bb88abd05 --- /dev/null +++ b/nuttx-configs/px4fmu-v4pro/include/board.h @@ -0,0 +1,433 @@ +/************************************************************************************ + * configs/px4fmu-v4pro/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2009, 2016 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * Kevin Lopez Alvarez + * + * 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_PX4FMUV4_PRO_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_PX4FMUV4_PRO_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + + +#include + + + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The PX4FMUV4-PRO uses a 24MHz crystal connected to the HSE. + * + * This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c: + * System Clock source : PLL (HSE) + * SYSCLK(Hz) : 180000000 Determined by PLL configuration + * HCLK(Hz) : 180000000 (STM32_RCC_CFGR_HPRE) + * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) + * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) + * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) + * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL) + * PLLM : 12 (STM32_PLLCFG_PLLM) + * PLLN : 180 (STM32_PLLCFG_PLLN) + * PLLP : 2 (STM32_PLLCFG_PLLP) + * PLLQ : 2 (STM32_PLLCFG_PPQ) + * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK + * Flash Latency(WS) : 5 + * Prefetch Buffer : OFF + * Instruction cache : ON + * Data cache : ON + * Require 48MHz for USB OTG FS, : Use PLLSA1M + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - On-board crystal frequency is 24MHz + * LSE - not installed + */ + +#define STM32_BOARD_XTAL 24000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL + +/* Main PLL Configuration. + * + * PLL source is HSE + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * = (24,000,000 / 12) * 180 + * = 369,000,000 + * SYSCLK = PLL_VCO / PLLP + * = 360,000,000 / 2 = 180,000,000 + * USB OTG FS, SDIO and RNG Clock is from PLL SAIP + * = 48,000,000 + */ + +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(12) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(180) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(2) +#define STM32_PLLCFG_PLLR RCC_PLLCFG_PLLR(2) + +/* Configure factors for PLLSAI clock */ + +#define STM32_RCC_PLLSAICFGR_PLLSAIN RCC_PLLSAICFGR_PLLSAIN(96) +#define STM32_RCC_PLLSAICFGR_PLLSAIP RCC_PLLSAICFGR_PLLSAIP(4) +#define STM32_RCC_PLLSAICFGR_PLLSAIQ RCC_PLLSAICFGR_PLLSAIQ(2) +#define STM32_RCC_PLLSAICFGR_PLLSAIR RCC_PLLSAICFGR_PLLSAIR(2) + +/* Configure Dedicated Clock Configuration Register */ + +#define STM32_RCC_DCKCFGR_PLLI2SDIVQ RCC_DCKCFGR_PLLI2SDIVQ(1) +#define STM32_RCC_DCKCFGR_PLLSAIDIVQ RCC_DCKCFGR_PLLSAIDIVQ(1) +#define STM32_RCC_DCKCFGR_PLLSAIDIVR RCC_DCKCFGR_PLLSAIDIVR_DIV2 +#define STM32_RCC_DCKCFGR_SAI1ASRC RCC_DCKCFGR_SAI1ASRC_PLLSAI +#define STM32_RCC_DCKCFGR_SAI1BSRC RCC_DCKCFGR_SAI1BSRC_PLLI2S +#define STM32_RCC_DCKCFGR_TIMPRE 0 +#define STM32_RCC_DCKCFGR_48MSEL RCC_DCKCFGR_48MSEL_PLLSAI +#define STM32_RCC_DCKCFGR_SDMMCSEL RCC_DCKCFGR_SDMMCSEL_48MHZ +#define STM32_RCC_DCKCFGR_DSISEL RCC_DCKCFGR_DSISEL_DSIPHY + +/* Configure factors for PLLI2S clock */ + +#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(96) +#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(4) +#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2) + + +#define STM32_SYSCLK_FREQUENCY 180000000ul + +/* AHB clock (HCLK) is SYSCLK (180MHz) */ + +#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 (45MHz) */ + +#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 (90MHz) */ + +#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) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8-11 are on APB2, others on APB1 + */ + +#define BOARD_TIM1_FREQUENCY STM32_APB2_TIM1_CLKIN +#define BOARD_TIM2_FREQUENCY STM32_APB1_TIM2_CLKIN +#define BOARD_TIM3_FREQUENCY STM32_APB1_TIM3_CLKIN +#define BOARD_TIM4_FREQUENCY STM32_APB1_TIM4_CLKIN +#define BOARD_TIM5_FREQUENCY STM32_APB1_TIM5_CLKIN +#define BOARD_TIM6_FREQUENCY STM32_APB1_TIM6_CLKIN +#define BOARD_TIM7_FREQUENCY STM32_APB1_TIM7_CLKIN +#define BOARD_TIM8_FREQUENCY STM32_APB2_TIM8_CLKIN +#define BOARD_TIM9_FREQUENCY STM32_APB2_TIM9_CLKIN +#define BOARD_TIM10_FREQUENCY STM32_APB2_TIM10_CLKIN +#define BOARD_TIM11_FREQUENCY STM32_APB2_TIM11_CLKIN +#define BOARD_TIM12_FREQUENCY STM32_APB1_TIM12_CLKIN +#define BOARD_TIM13_FREQUENCY STM32_APB1_TIM13_CLKIN +#define BOARD_TIM14_FREQUENCY STM32_APB1_TIM14_CLKIN + +/* 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!!! + * + * SDIOCLK =48MHz, SDMMC_CK=SDIOCLK/(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 SDIO_CLKCR_EDGE SDIO_CLKCR_NEGEDGE + +#define SDIO_INIT_CLKDIV (118 << SDIO_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: SDIOCLK=48MHz, SDMMC_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDMMC_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_SDIO_DMA +# define SDIO_MMCXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA ON: SDIOCLK=48MHz, SDMMC_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDMMC_CK=SDIOCLK/(2+2)=12 MHz + */ +//TODO #warning "Check Freq for 24mHz" + +#ifdef CONFIG_SDIO_DMA +# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA Channel/Stream Selections *****************************************************/ +/* Stream selections are arbitrary for now but might become important in the future + * is we set aside more DMA channels/streams. + * + * SDIO DMA + *   DMAMAP_SDIO_1 = Channel 4, Stream 3 <- may later be used by SPI DMA + *   DMAMAP_SDIO_2 = Channel 4, Stream 6 + */ + +#define DMAMAP_SDIO DMAMAP_SDIO_1 + + +/* FLASH wait states + * + * --------- ---------- ----------- --------- + * VDD MAX SYSCLK WAIT STATES OVERDRIVE + * --------- ---------- ----------- --------- + * 1.7-2.1 V 168 MHz 8 OFF + * 2.1-2.4 V 180 MHz 8 ON + * 2.4-2.7 V 180 MHz 7 ON + * 2.7-3.6 V 180 MHz 5 ON + * --------- ---------- ----------- -------- + *- + */ + +#define BOARD_FLASH_WAITSTATES 5 + +/* LED definitions ******************************************************************/ +/* The px4fmu-v4pro board has numerous LEDs. + * FMU_LED_RED, FMU_LED_GREEN & FMU_LED_BLUE are directly connected and + * can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + + /* LED index values for use with board_userled() */ + + #define BOARD_LED1 0 + #define BOARD_LED2 1 + #define BOARD_LED3 2 + #define BOARD_NLEDS 3 + + #define BOARD_LED_RED BOARD_LED1 + #define BOARD_LED_GREEN BOARD_LED2 + #define BOARD_LED_BLUE BOARD_LED3 + + /* LED bits for use with board_userled_all() */ + + #define BOARD_LED1_BIT (1 << BOARD_LED1) + #define BOARD_LED2_BIT (1 << BOARD_LED2) + #define BOARD_LED3_BIT (1 << BOARD_LED3) + + /* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + + #define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ + #define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ + #define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ + #define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ + #define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ + #define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ + #define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ + #define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ + #define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + + /* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + + +/* Alternate function pin selections ************************************************/ + +/* + * UARTs. + */ +#define GPIO_USART1_RX GPIO_USART1_RX_2 /* ESP8266 */ +#define GPIO_USART1_TX GPIO_USART1_TX_2 + +#define GPIO_USART2_RX GPIO_USART2_RX_2 +#define GPIO_USART2_TX GPIO_USART2_TX_2 +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 +#define GPIO_USART2_CTS GPIO_USART2_CTS_2 + +#define GPIO_USART3_RX GPIO_USART3_RX_3 +#define GPIO_USART3_TX GPIO_USART3_TX_3 +#define GPIO_USART3_RTS GPIO_USART3_RTS_2 +#define GPIO_USART3_CTS GPIO_USART3_CTS_2 + +#define GPIO_UART4_RX GPIO_UART4_RX_1 +#define GPIO_UART4_TX GPIO_UART4_TX_1 + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* RC_INPUT */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 + +#define GPIO_UART7_RX GPIO_UART7_RX_1 +#define GPIO_UART7_TX GPIO_UART7_TX_1 + +/* UART8 has no alternate pin config */ + +/* 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 onboard transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 + +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 +#define GPIO_CAN2_TX GPIO_CAN2_RX_1 + +/* + * I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + */ +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 +#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) + + +/* + * SPI + * + * There are sensors on SPI1, and SPI2 is connected to the FRAM. + + */ +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_1 + +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 +#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1 +#define GPIO_SPI5_NSS GPIO_SPI5_NSS_1 + + +/************************************************************************************ + * 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. + * + ************************************************************************************/ + +EXTERN void stm32_boardinitialize(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __NUTTX_CONFIG_PX4FMUV4_PRO_INCLUDE_BOARD_H */ diff --git a/nuttx-configs/px4fmu-v4pro/include/nsh_romfsimg.h b/nuttx-configs/px4fmu-v4pro/include/nsh_romfsimg.h new file mode 100644 index 0000000000..15e4e7a8d5 --- /dev/null +++ b/nuttx-configs/px4fmu-v4pro/include/nsh_romfsimg.h @@ -0,0 +1,42 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * 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; diff --git a/nuttx-configs/px4fmu-v4pro/nsh/Make.defs b/nuttx-configs/px4fmu-v4pro/nsh/Make.defs new file mode 100644 index 0000000000..bb3ed386e6 --- /dev/null +++ b/nuttx-configs/px4fmu-v4pro/nsh/Make.defs @@ -0,0 +1,164 @@ +############################################################################ +# configs/px4fmu-v4pro/nsh/Make.defs +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +MAXOPTIMIZATION = -Os +ARCHCPUFLAGS = -mcpu=cortex-m4 \ + -mthumb \ + -march=armv7e-m \ + -mfpu=fpv4-sp-d16 \ + -mfloat-abi=hard + +# 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/mknulldeps.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 + +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.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +# Produce partially-linked $1 from files in $2 + +define PRELINK + @echo "PRELINK: $1" + $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 +endef + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = diff --git a/nuttx-configs/px4fmu-v4pro/nsh/defconfig b/nuttx-configs/px4fmu-v4pro/nsh/defconfig new file mode 100644 index 0000000000..5703b4cb47 --- /dev/null +++ b/nuttx-configs/px4fmu-v4pro/nsh/defconfig @@ -0,0 +1,1556 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_DEFAULT_SMALL is not set +CONFIG_HOST_LINUX=y +# CONFIG_HOST_OSX is not set +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +CONFIG_BUILD_FLAT=y +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y +# CONFIG_UBOOT_UIMAGE is not set + +# +# Customize Header Files +# +# CONFIG_ARCH_STDINT_H is not set +# CONFIG_ARCH_STDBOOL_H is not set +CONFIG_ARCH_MATH_H=y +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set +# CONFIG_ARCH_DEBUG_H is not set + +# +# Debug Options +# +CONFIG_DEBUG_ALERT=y +# CONFIG_DEBUG_FEATURES is not set +CONFIG_ARCH_HAVE_STACKCHECK=y +CONFIG_STACK_COLORATION=y +CONFIG_ARCH_HAVE_HEAPCHECK=y +# CONFIG_HEAP_COLORATION is not set +CONFIG_DEBUG_SYMBOLS=y +CONFIG_ARCH_HAVE_CUSTOMOPT=y +CONFIG_DEBUG_NOOPT=y +# CONFIG_DEBUG_CUSTOMOPT is not set +# CONFIG_DEBUG_FULLOPT is not set + +# +# System Type +# +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_RENESAS is not set +# CONFIG_ARCH_RISCV is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_XTENSA is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_A1X is not set +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_EFM32 is not set +# CONFIG_ARCH_CHIP_IMX1 is not set +# CONFIG_ARCH_CHIP_IMX6 is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_TIVA is not set +# CONFIG_ARCH_CHIP_LPC11XX is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAMA5 is not set +# CONFIG_ARCH_CHIP_SAMD is not set +# CONFIG_ARCH_CHIP_SAML is not set +# CONFIG_ARCH_CHIP_SAM34 is not set +# CONFIG_ARCH_CHIP_SAMV7 is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STM32F7 is not set +# CONFIG_ARCH_CHIP_STM32L4 is not set +# CONFIG_ARCH_CHIP_STR71X is not set +# CONFIG_ARCH_CHIP_TMS570 is not set +# CONFIG_ARCH_CHIP_MOXART is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM3 is not set +CONFIG_ARCH_CORTEXM4=y +# CONFIG_ARCH_CORTEXM7 is not set +# CONFIG_ARCH_CORTEXA5 is not set +# CONFIG_ARCH_CORTEXA8 is not set +# CONFIG_ARCH_CORTEXA9 is not set +# CONFIG_ARCH_CORTEXR4 is not set +# CONFIG_ARCH_CORTEXR4F is not set +# CONFIG_ARCH_CORTEXR5 is not set +# CONFIG_ARCH_CORTEX5F is not set +# CONFIG_ARCH_CORTEXR7 is not set +# CONFIG_ARCH_CORTEXR7F is not set +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARM_TOOLCHAIN_IAR is not set +CONFIG_ARM_TOOLCHAIN_GNU=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARCH_HAVE_CMNVECTOR=y +CONFIG_ARMV7M_CMNVECTOR=y +# CONFIG_ARMV7M_LAZYFPU is not set +CONFIG_ARCH_HAVE_FPU=y +# CONFIG_ARCH_HAVE_DPFPU is not set +CONFIG_ARCH_FPU=y +# CONFIG_ARCH_HAVE_TRUSTZONE is not set +CONFIG_ARM_HAVE_MPU_UNIFIED=y +# CONFIG_ARM_MPU is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_HAVE_ICACHE is not set +# CONFIG_ARMV7M_HAVE_DCACHE is not set +# CONFIG_ARMV7M_HAVE_ITCM is not set +# CONFIG_ARMV7M_HAVE_DTCM is not set +# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL=y +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +CONFIG_SERIAL_TERMIOS=y +CONFIG_SDIO_DMA=y +# CONFIG_SDIO_WIDTH_D1_ONLY is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32L162ZD is not set +# CONFIG_ARCH_CHIP_STM32L162VE is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F102CB is not set +# CONFIG_ARCH_CHIP_STM32F103T8 is not set +# CONFIG_ARCH_CHIP_STM32F103TB is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103CB is not set +# CONFIG_ARCH_CHIP_STM32F103R8 is not set +# CONFIG_ARCH_CHIP_STM32F103RB is not set +# CONFIG_ARCH_CHIP_STM32F103RC is not set +# CONFIG_ARCH_CHIP_STM32F103RD is not set +# CONFIG_ARCH_CHIP_STM32F103RE is not set +# CONFIG_ARCH_CHIP_STM32F103RG is not set +# CONFIG_ARCH_CHIP_STM32F103V8 is not set +# CONFIG_ARCH_CHIP_STM32F103VB is not set +# CONFIG_ARCH_CHIP_STM32F103VC is not set +# CONFIG_ARCH_CHIP_STM32F103VE is not set +# CONFIG_ARCH_CHIP_STM32F103ZE is not set +# CONFIG_ARCH_CHIP_STM32F105VB is not set +# CONFIG_ARCH_CHIP_STM32F105RB is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F205RG is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F207ZE is not set +# CONFIG_ARCH_CHIP_STM32F302K6 is not set +# CONFIG_ARCH_CHIP_STM32F302K8 is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303K6 is not set +# CONFIG_ARCH_CHIP_STM32F303K8 is not set +# CONFIG_ARCH_CHIP_STM32F303C6 is not set +# CONFIG_ARCH_CHIP_STM32F303C8 is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303RD is not set +# CONFIG_ARCH_CHIP_STM32F303RE is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +# CONFIG_ARCH_CHIP_STM32F372C8 is not set +# CONFIG_ARCH_CHIP_STM32F372R8 is not set +# CONFIG_ARCH_CHIP_STM32F372V8 is not set +# CONFIG_ARCH_CHIP_STM32F372CB is not set +# CONFIG_ARCH_CHIP_STM32F372RB is not set +# CONFIG_ARCH_CHIP_STM32F372VB is not set +# CONFIG_ARCH_CHIP_STM32F372CC is not set +# CONFIG_ARCH_CHIP_STM32F372RC is not set +# CONFIG_ARCH_CHIP_STM32F372VC is not set +# CONFIG_ARCH_CHIP_STM32F373C8 is not set +# CONFIG_ARCH_CHIP_STM32F373R8 is not set +# CONFIG_ARCH_CHIP_STM32F373V8 is not set +# CONFIG_ARCH_CHIP_STM32F373CB is not set +# CONFIG_ARCH_CHIP_STM32F373RB is not set +# CONFIG_ARCH_CHIP_STM32F373VB is not set +# CONFIG_ARCH_CHIP_STM32F373CC is not set +# CONFIG_ARCH_CHIP_STM32F373RC is not set +# CONFIG_ARCH_CHIP_STM32F373VC is not set +# CONFIG_ARCH_CHIP_STM32F401RE is not set +# CONFIG_ARCH_CHIP_STM32F411RE is not set +# CONFIG_ARCH_CHIP_STM32F411VE is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_ARCH_CHIP_STM32F429V is not set +# CONFIG_ARCH_CHIP_STM32F429Z is not set +# CONFIG_ARCH_CHIP_STM32F429I is not set +# CONFIG_ARCH_CHIP_STM32F429B is not set +# CONFIG_ARCH_CHIP_STM32F429N is not set +# CONFIG_ARCH_CHIP_STM32F446M is not set +# CONFIG_ARCH_CHIP_STM32F446R is not set +# CONFIG_ARCH_CHIP_STM32F446V is not set +# CONFIG_ARCH_CHIP_STM32F446Z is not set +# CONFIG_ARCH_CHIP_STM32F469A is not set +CONFIG_ARCH_CHIP_STM32F469I=y +# CONFIG_ARCH_CHIP_STM32F469B is not set +# CONFIG_ARCH_CHIP_STM32F469N is not set +# CONFIG_STM32_FLASH_CONFIG_DEFAULT is not set +# CONFIG_STM32_FLASH_CONFIG_4 is not set +# CONFIG_STM32_FLASH_CONFIG_6 is not set +# CONFIG_STM32_FLASH_CONFIG_8 is not set +# CONFIG_STM32_FLASH_CONFIG_B is not set +# CONFIG_STM32_FLASH_CONFIG_C is not set +# CONFIG_STM32_FLASH_CONFIG_D is not set +# CONFIG_STM32_FLASH_CONFIG_E is not set +# CONFIG_STM32_FLASH_CONFIG_F is not set +# CONFIG_STM32_FLASH_CONFIG_G is not set +CONFIG_STM32_FLASH_CONFIG_I=y +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_USBACCESSLINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +# CONFIG_STM32_STM32F20XX is not set +# CONFIG_STM32_STM32F205 is not set +# CONFIG_STM32_STM32F207 is not set +# CONFIG_STM32_STM32F30XX is not set +# CONFIG_STM32_STM32F302 is not set +# CONFIG_STM32_STM32F303 is not set +# CONFIG_STM32_STM32F37XX is not set +CONFIG_STM32_STM32F40XX=y +# CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F411 is not set +# CONFIG_STM32_STM32F405 is not set +# CONFIG_STM32_STM32F407 is not set +# CONFIG_STM32_STM32F427 is not set +# CONFIG_STM32_STM32F429 is not set +# CONFIG_STM32_STM32F446 is not set +CONFIG_STM32_STM32F469=y +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +CONFIG_STM32_HAVE_CCM=y +# CONFIG_STM32_HAVE_USBDEV is not set +CONFIG_STM32_HAVE_OTGFS=y +CONFIG_STM32_HAVE_FSMC=y +CONFIG_STM32_HAVE_LTDC=y +CONFIG_STM32_HAVE_USART3=y +CONFIG_STM32_HAVE_UART4=y +CONFIG_STM32_HAVE_UART5=y +CONFIG_STM32_HAVE_USART6=y +CONFIG_STM32_HAVE_UART7=y +CONFIG_STM32_HAVE_UART8=y +CONFIG_STM32_HAVE_TIM1=y +# CONFIG_STM32_HAVE_TIM2 is not set +CONFIG_STM32_HAVE_TIM3=y +CONFIG_STM32_HAVE_TIM4=y +# CONFIG_STM32_HAVE_TIM5 is not set +CONFIG_STM32_HAVE_TIM6=y +CONFIG_STM32_HAVE_TIM7=y +CONFIG_STM32_HAVE_TIM8=y +CONFIG_STM32_HAVE_TIM9=y +CONFIG_STM32_HAVE_TIM10=y +CONFIG_STM32_HAVE_TIM11=y +CONFIG_STM32_HAVE_TIM12=y +CONFIG_STM32_HAVE_TIM13=y +CONFIG_STM32_HAVE_TIM14=y +# CONFIG_STM32_HAVE_TIM15 is not set +# CONFIG_STM32_HAVE_TIM16 is not set +# CONFIG_STM32_HAVE_TIM17 is not set +CONFIG_STM32_HAVE_ADC2=y +CONFIG_STM32_HAVE_ADC3=y +# CONFIG_STM32_HAVE_ADC4 is not set +CONFIG_STM32_HAVE_ADC1_DMA=y +# CONFIG_STM32_HAVE_ADC2_DMA is not set +# CONFIG_STM32_HAVE_ADC3_DMA is not set +# CONFIG_STM32_HAVE_ADC4_DMA is not set +CONFIG_STM32_HAVE_CAN1=y +CONFIG_STM32_HAVE_CAN2=y +CONFIG_STM32_HAVE_DAC1=y +CONFIG_STM32_HAVE_DAC2=y +CONFIG_STM32_HAVE_RNG=y +CONFIG_STM32_HAVE_ETHMAC=y +CONFIG_STM32_HAVE_I2C2=y +CONFIG_STM32_HAVE_I2C3=y +CONFIG_STM32_HAVE_SPI2=y +CONFIG_STM32_HAVE_SPI3=y +CONFIG_STM32_HAVE_SPI4=y +CONFIG_STM32_HAVE_SPI5=y +CONFIG_STM32_HAVE_SPI6=y +CONFIG_STM32_HAVE_SAIPLL=y +CONFIG_STM32_HAVE_I2SPLL=y +CONFIG_STM32_ADC1=y +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +CONFIG_STM32_BKPSRAM=y +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +CONFIG_STM32_CCMDATARAM=y +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_CRYP is not set +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=y +# CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_LTDC is not set +CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGHS is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_RNG is not set +CONFIG_STM32_SDIO=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_SPI2=y +# CONFIG_STM32_SPI3 is not set +# CONFIG_STM32_SPI4 is not set +CONFIG_STM32_SPI5=y +CONFIG_STM32_SPI6=y +CONFIG_STM32_SYSCFG=y +CONFIG_STM32_TIM1=y +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +CONFIG_STM32_TIM4=y +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +CONFIG_STM32_TIM8=y +CONFIG_STM32_TIM9=y +CONFIG_STM32_TIM10=y +CONFIG_STM32_TIM11=y +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +CONFIG_STM32_USART1=y +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_STM32_UART4=y +# CONFIG_STM32_UART5 is not set +CONFIG_STM32_USART6=y +CONFIG_STM32_UART7=y +CONFIG_STM32_UART8=y +# CONFIG_STM32_IWDG is not set +CONFIG_STM32_WWDG=y +CONFIG_STM32_ADC=y +CONFIG_STM32_SPI=y +CONFIG_STM32_I2C=y +# CONFIG_STM32_NOEXT_VECTORS is not set + +# +# Alternate Pin Mapping +# +CONFIG_STM32_FLASH_PREFETCH=y +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +CONFIG_STM32_SAIPLL=y +CONFIG_STM32_I2SPLL=y +# CONFIG_STM32_CCMEXCLUDE is not set +# CONFIG_STM32_CCM_PROCFS is not set +CONFIG_STM32_DMACAPABLE=y +CONFIG_USBDEV_VBUSSENSING=y + +# +# Timer Configuration +# +# CONFIG_STM32_ONESHOT is not set +# CONFIG_STM32_FREERUN is not set +# CONFIG_STM32_TIM1_PWM is not set +# CONFIG_STM32_TIM4_PWM is not set +# CONFIG_STM32_TIM8_PWM is not set +# CONFIG_STM32_TIM9_PWM is not set +# CONFIG_STM32_TIM10_PWM is not set +# CONFIG_STM32_TIM11_PWM is not set +# CONFIG_STM32_TIM1_ADC is not set +# CONFIG_STM32_TIM4_ADC is not set +# CONFIG_STM32_TIM8_ADC is not set +# CONFIG_STM32_TIM1_CAP is not set +# CONFIG_STM32_TIM3_CAP is not set +# CONFIG_STM32_TIM4_CAP is not set +# CONFIG_STM32_TIM8_CAP is not set +# CONFIG_STM32_TIM9_CAP is not set +# CONFIG_STM32_TIM10_CAP is not set +# CONFIG_STM32_TIM11_CAP is not set +# CONFIG_STM32_TIM12_CAP is not set +# CONFIG_STM32_TIM13_CAP is not set +# CONFIG_STM32_TIM14_CAP is not set + +# +# ADC Configuration +# +# CONFIG_STM32_ADC1_DMA is not set +CONFIG_STM32_USART=y +CONFIG_STM32_SERIALDRIVER=y + +# +# U[S]ART Configuration +# + +# +# U[S]ART Device Configuration +# +CONFIG_STM32_USART1_SERIALDRIVER=y +# CONFIG_STM32_USART1_1WIREDRIVER is not set +# CONFIG_USART1_RS485 is not set +CONFIG_USART1_RXDMA=y +CONFIG_STM32_USART2_SERIALDRIVER=y +# CONFIG_STM32_USART2_1WIREDRIVER is not set +# CONFIG_USART2_RS485 is not set +CONFIG_USART2_RXDMA=y +CONFIG_STM32_USART3_SERIALDRIVER=y +# CONFIG_STM32_USART3_1WIREDRIVER is not set +# CONFIG_USART3_RS485 is not set +CONFIG_USART3_RXDMA=y +CONFIG_STM32_UART4_SERIALDRIVER=y +# CONFIG_STM32_UART4_1WIREDRIVER is not set +# CONFIG_UART4_RS485 is not set +CONFIG_UART4_RXDMA=y +CONFIG_STM32_USART6_SERIALDRIVER=y +# CONFIG_STM32_USART6_1WIREDRIVER is not set +# CONFIG_USART6_RS485 is not set +CONFIG_USART6_RXDMA=y +CONFIG_STM32_UART7_SERIALDRIVER=y +# CONFIG_STM32_UART7_1WIREDRIVER is not set +# CONFIG_UART7_RS485 is not set +CONFIG_UART7_RXDMA=y +CONFIG_STM32_UART8_SERIALDRIVER=y +# CONFIG_STM32_UART8_1WIREDRIVER is not set +# CONFIG_UART8_RS485 is not set +CONFIG_UART8_RXDMA=y + +# +# Serial Driver Configuration +# +CONFIG_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32_FLOWCONTROL_BROKEN=y +CONFIG_STM32_USART_BREAKS=y +CONFIG_STM32_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32_USART_SINGLEWIRE=y + +# +# SPI Configuration +# +# CONFIG_STM32_SPI_INTERRUPTS is not set +# CONFIG_STM32_SPI_DMA is not set + +# +# I2C Configuration +# +# CONFIG_STM32_I2C_ALT is not set +# CONFIG_STM32_I2C_DYNTIMEO is not set +CONFIG_STM32_I2CTIMEOSEC=0 +CONFIG_STM32_I2CTIMEOMS=10 +CONFIG_STM32_I2CTIMEOTICKS=10 +# CONFIG_STM32_I2C_DUTY16_9 is not set + +# +# SDIO Configuration +# +CONFIG_SDIO_DMAPRIO=0x00010000 +CONFIG_STM32_BBSRAM=y +CONFIG_STM32_BBSRAM_FILES=4 +CONFIG_STM32_SAVE_CRASHDUMP=y +# CONFIG_STM32_HAVE_RTC_COUNTER is not set +# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set +CONFIG_RTC_MAGIC_REG=1 +CONFIG_RTC_MAGIC=0xfacefeee +# CONFIG_RTC_LSECLOCK is not set +# CONFIG_RTC_LSICLOCK is not set +CONFIG_RTC_HSECLOCK=y + +# +# USB FS Host Configuration +# + +# +# USB HS Host Configuration +# + +# +# USB Host Debug Configuration +# + +# +# USB Device Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +CONFIG_ARCH_DMA=y +CONFIG_ARCH_HAVE_IRQPRIO=y +# CONFIG_ARCH_L2CACHE is not set +# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set +# CONFIG_ARCH_HAVE_ADDRENV is not set +# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set +# CONFIG_ARCH_HAVE_MULTICPU is not set +CONFIG_ARCH_HAVE_VFORK=y +# CONFIG_ARCH_HAVE_MMU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARCH_NAND_HWECC is not set +# CONFIG_ARCH_HAVE_EXTCLK is not set +# CONFIG_ARCH_HAVE_POWEROFF is not set +CONFIG_ARCH_HAVE_RESET=y +# CONFIG_ARCH_USE_MPU is not set +CONFIG_ARCH_IRQPRIO=y +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_IDLE_CUSTOM is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set + +# +# Interrupt options +# +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=750 +CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y +CONFIG_ARCH_HIPRI_INTERRUPT=y + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Boot Memory Configuration +# +CONFIG_RAM_START=0x20000000 +CONFIG_RAM_SIZE=327680 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_PX4FMU_V4PRO=y +CONFIG_ARCH_BOARD="px4fmu-v4pro" + +# +# Custom Board Configuration +# +# CONFIG_BOARD_CUSTOM_LEDS is not set +# CONFIG_BOARD_CUSTOM_BUTTONS is not set +CONFIG_BOARD_HAS_PROBES=y +# CONFIG_BOARD_USE_PROBES is not set + +# +# Common Board Options +# + +# +# Board-Specific Options +# +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_RESET_ON_CRASH=y +CONFIG_LIB_BOARDCTL=y +# CONFIG_BOARDCTL_RESET is not set +# CONFIG_BOARDCTL_UNIQUEID is not set +CONFIG_BOARDCTL_USBDEVCTRL=y +# CONFIG_BOARDCTL_TSCTEST is not set +# CONFIG_BOARDCTL_ADCTEST is not set +# CONFIG_BOARDCTL_PWMTEST is not set +# CONFIG_BOARDCTL_GRAPHICS is not set +# CONFIG_BOARDCTL_IOCTL is not set + +# +# RTOS Features +# +# CONFIG_DISABLE_OS_API is not set + +# +# Clocks and Timers +# +CONFIG_ARCH_HAVE_TICKLESS=y +# CONFIG_SCHED_TICKLESS is not set +CONFIG_USEC_PER_TICK=1000 +# CONFIG_SYSTEM_TIME64 is not set +# CONFIG_CLOCK_MONOTONIC is not set +CONFIG_ARCH_HAVE_TIMEKEEPING=y +# CONFIG_JULIAN_TIME is not set +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=50 +CONFIG_WDOG_INTRESERVE=4 +CONFIG_PREALLOC_TIMERS=50 + +# +# Tasks and Scheduling +# +# CONFIG_INIT_NONE is not set +CONFIG_INIT_ENTRYPOINT=y +# CONFIG_INIT_FILEPATH is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_RR_INTERVAL=0 +# CONFIG_SCHED_SPORADIC is not set +CONFIG_TASK_NAME_SIZE=24 +CONFIG_MAX_TASKS=32 +# CONFIG_SCHED_HAVE_PARENT is not set +CONFIG_SCHED_WAITPID=y + +# +# Pthread Options +# +# CONFIG_MUTEX_TYPES is not set +CONFIG_NPTHREAD_KEYS=4 + +# +# Performance Monitoring +# +# CONFIG_SCHED_CPULOAD is not set +CONFIG_SCHED_INSTRUMENTATION=y +# CONFIG_SCHED_INSTRUMENTATION_PREEMPTION is not set +# CONFIG_SCHED_INSTRUMENTATION_CSECTION is not set +# CONFIG_SCHED_INSTRUMENTATION_BUFFER is not set + +# +# Files and I/O +# +CONFIG_DEV_CONSOLE=y +# CONFIG_FDCLONE_DISABLE is not set +CONFIG_FDCLONE_STDIO=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_NFILE_DESCRIPTORS=51 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=8 + +# +# RTOS hooks +# +# CONFIG_BOARD_INITIALIZE is not set +# CONFIG_SCHED_STARTHOOK is not set +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_ATEXIT_MAX=1 +# CONFIG_SCHED_ONEXIT is not set +# CONFIG_SIG_EVTHREAD is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=4 + +# +# POSIX Message Queue Options +# +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +# CONFIG_MODULE is not set + +# +# Work queue support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=192 +CONFIG_SCHED_HPWORKPERIOD=5000 +CONFIG_SCHED_HPWORKSTACKSIZE=1800 +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPNTHREADS=1 +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKPRIOMAX=176 +CONFIG_SCHED_LPWORKPERIOD=50000 +CONFIG_SCHED_LPWORKSTACKSIZE=1800 + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=500 +CONFIG_USERMAIN_STACKSIZE=2500 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_PTHREAD_STACK_DEFAULT=2048 +# CONFIG_LIB_SYSCALL is not set + +# +# Device Drivers +# +# CONFIG_DISABLE_POLL is not set +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_DEV_URANDOM is not set +# CONFIG_DEV_LOOP is not set + +# +# Buffering +# +# CONFIG_DRVR_WRITEBUFFER is not set +# CONFIG_DRVR_READAHEAD is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set +# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set +# CONFIG_PWM is not set +CONFIG_ARCH_HAVE_I2CRESET=y +CONFIG_I2C=y +# CONFIG_I2C_SLAVE is not set +# CONFIG_I2C_POLLED is not set +CONFIG_I2C_RESET=y +# CONFIG_I2C_TRACE is not set +# CONFIG_I2C_DRIVER is not set +CONFIG_SPI=y +# CONFIG_SPI_SLAVE is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_SPI_CALLBACK is not set +# CONFIG_SPI_HWFEATURES is not set +# CONFIG_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +# CONFIG_SPI_BITORDER is not set +# CONFIG_SPI_CS_DELAY_CONTROL is not set +# CONFIG_SPI_DRIVER is not set +# CONFIG_SPI_BITBANG is not set +# CONFIG_I2S is not set + +# +# Timer Driver Support +# +# CONFIG_TIMER is not set +# CONFIG_ONESHOT is not set +CONFIG_RTC=y +CONFIG_RTC_DATETIME=y +# CONFIG_RTC_ALARM is not set +# CONFIG_RTC_DRIVER is not set +# CONFIG_RTC_EXTERNAL is not set +CONFIG_WATCHDOG=y +CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0" +# CONFIG_TIMERS_CS2100CP is not set +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_VIDEO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set + +# +# IO Expander/GPIO Support +# +# CONFIG_IOEXPANDER is not set +# CONFIG_DEV_GPIO is not set + +# +# LCD Driver Support +# +# CONFIG_LCD is not set +# CONFIG_SLCD is not set + +# +# LED Support +# +# CONFIG_RGBLED is not set +# CONFIG_PCA9635PW is not set +# CONFIG_NCP5623C is not set +CONFIG_MMCSD=y +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +CONFIG_MMCSD_MULTIBLOCK_DISABLE=y +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_HAVECARDDETECT is not set +# CONFIG_MMCSD_SPI is not set +CONFIG_ARCH_HAVE_SDIO=y +CONFIG_ARCH_HAVE_SDIOWAIT_WRCOMPLETE=y +CONFIG_MMCSD_SDIO=y +CONFIG_SDIO_PREFLIGHT=y +# CONFIG_SDIO_MUXBUS is not set +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +# CONFIG_SDIO_BLOCKSETUP is not set +# CONFIG_MODEM is not set +CONFIG_MTD=y + +# +# MTD Configuration +# +CONFIG_MTD_PARTITION=y +# CONFIG_MTD_SECT512 is not set +# CONFIG_MTD_PARTITION_NAMES is not set +CONFIG_MTD_BYTE_WRITE=y +# CONFIG_MTD_PROGMEM is not set +# CONFIG_MTD_CONFIG is not set + +# +# MTD Device Drivers +# +# CONFIG_MTD_NAND is not set +# CONFIG_RAMMTD is not set +# CONFIG_FILEMTD is not set +# CONFIG_MTD_AT24XX is not set +# CONFIG_MTD_AT25 is not set +# CONFIG_MTD_AT45DB is not set +# CONFIG_MTD_IS25XP is not set +# CONFIG_MTD_M25P is not set +# CONFIG_MTD_MX25L is not set +# CONFIG_MTD_S25FL1 is not set +# CONFIG_MTD_N25QXXX is not set +# CONFIG_MTD_SMART is not set +CONFIG_MTD_RAMTRON=y +CONFIG_RAMTRON_WRITEWAIT=y +CONFIG_RAMTRON_SETSPEED=y +# CONFIG_MTD_SST25 is not set +# CONFIG_MTD_SST25XX is not set +# CONFIG_MTD_SST26 is not set +# CONFIG_MTD_SST39FV is not set +# CONFIG_MTD_W25 is not set +# CONFIG_EEPROM is not set +CONFIG_PIPES=y +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=1024 +CONFIG_DEV_FIFO_SIZE=0 +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +CONFIG_SERIAL_REMOVABLE=y +CONFIG_SERIAL_CONSOLE=y +# CONFIG_16550_UART is not set +# CONFIG_UART_SERIALDRIVER is not set +# CONFIG_UART0_SERIALDRIVER is not set +# CONFIG_UART1_SERIALDRIVER is not set +# CONFIG_UART2_SERIALDRIVER is not set +# CONFIG_UART3_SERIALDRIVER is not set +CONFIG_UART4_SERIALDRIVER=y +# CONFIG_UART5_SERIALDRIVER is not set +# CONFIG_UART6_SERIALDRIVER is not set +CONFIG_UART7_SERIALDRIVER=y +CONFIG_UART8_SERIALDRIVER=y +# CONFIG_SCI0_SERIALDRIVER is not set +# CONFIG_SCI1_SERIALDRIVER is not set +# CONFIG_USART0_SERIALDRIVER is not set +CONFIG_USART1_SERIALDRIVER=y +CONFIG_USART2_SERIALDRIVER=y +CONFIG_USART3_SERIALDRIVER=y +# CONFIG_USART4_SERIALDRIVER is not set +# CONFIG_USART5_SERIALDRIVER is not set +CONFIG_USART6_SERIALDRIVER=y +# CONFIG_USART7_SERIALDRIVER is not set +# CONFIG_USART8_SERIALDRIVER is not set +# CONFIG_OTHER_UART_SERIALDRIVER is not set +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_SERIAL_NPOLLWAITERS=2 +CONFIG_SERIAL_IFLOWCONTROL=y +CONFIG_SERIAL_OFLOWCONTROL=y +# CONFIG_SERIAL_DMA is not set +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_IFLOWCONTROL_LOWER_WATERMARK=10 +CONFIG_SERIAL_IFLOWCONTROL_UPPER_WATERMARK=90 +CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y +# CONFIG_USART1_SERIAL_CONSOLE is not set +# CONFIG_USART2_SERIAL_CONSOLE is not set +# CONFIG_USART3_SERIAL_CONSOLE is not set +# CONFIG_UART4_SERIAL_CONSOLE is not set +# CONFIG_USART6_SERIAL_CONSOLE is not set +CONFIG_UART7_SERIAL_CONSOLE=y +# CONFIG_UART8_SERIAL_CONSOLE is not set +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART1 Configuration +# +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=2500 +CONFIG_USART1_BAUD=115200 +CONFIG_USART1_BITS=8 +CONFIG_USART1_PARITY=0 +CONFIG_USART1_2STOP=0 +# CONFIG_USART1_IFLOWCONTROL is not set +# CONFIG_USART1_OFLOWCONTROL is not set +# CONFIG_USART1_DMA is not set + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=1100 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +# CONFIG_USART2_DMA is not set + +# +# USART3 Configuration +# +CONFIG_USART3_RXBUFSIZE=300 +CONFIG_USART3_TXBUFSIZE=300 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_BITS=8 +CONFIG_USART3_PARITY=0 +CONFIG_USART3_2STOP=0 +CONFIG_USART3_IFLOWCONTROL=y +CONFIG_USART3_OFLOWCONTROL=y +# CONFIG_USART3_DMA is not set + +# +# UART4 Configuration +# +CONFIG_UART4_RXBUFSIZE=300 +CONFIG_UART4_TXBUFSIZE=300 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_BITS=8 +CONFIG_UART4_PARITY=0 +CONFIG_UART4_2STOP=0 +# CONFIG_UART4_IFLOWCONTROL is not set +# CONFIG_UART4_OFLOWCONTROL is not set +# CONFIG_UART4_DMA is not set + +# +# USART6 Configuration +# +CONFIG_USART6_RXBUFSIZE=300 +CONFIG_USART6_TXBUFSIZE=300 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_BITS=8 +CONFIG_USART6_PARITY=0 +CONFIG_USART6_2STOP=0 +# CONFIG_USART6_IFLOWCONTROL is not set +# CONFIG_USART6_OFLOWCONTROL is not set +# CONFIG_USART6_DMA is not set + +# +# UART7 Configuration +# +CONFIG_UART7_RXBUFSIZE=300 +CONFIG_UART7_TXBUFSIZE=300 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_BITS=8 +CONFIG_UART7_PARITY=0 +CONFIG_UART7_2STOP=0 +# CONFIG_UART7_IFLOWCONTROL is not set +# CONFIG_UART7_OFLOWCONTROL is not set +# CONFIG_UART7_DMA is not set + +# +# UART8 Configuration +# +CONFIG_UART8_RXBUFSIZE=300 +CONFIG_UART8_TXBUFSIZE=300 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_BITS=8 +CONFIG_UART8_PARITY=0 +CONFIG_UART8_2STOP=0 +# CONFIG_UART8_IFLOWCONTROL is not set +# CONFIG_UART8_OFLOWCONTROL is not set +# CONFIG_UART8_DMA is not set +# CONFIG_PSEUDOTERM is not set +CONFIG_USBDEV=y + +# +# USB Device Controller Driver Options +# +# CONFIG_USBDEV_ISOCHRONOUS is not set +# CONFIG_USBDEV_DUALSPEED is not set +# CONFIG_USBDEV_SELFPOWERED is not set +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +# CONFIG_USBDEV_DMA is not set +# CONFIG_ARCH_USBDEV_STALLQUEUE is not set +# CONFIG_USBDEV_TRACE is not set + +# +# USB Device Class Driver Options +# +# CONFIG_USBDEV_COMPOSITE is not set +# CONFIG_PL2303 is not set +CONFIG_CDCACM=y +# CONFIG_CDCACM_CONSOLE is not set +CONFIG_CDCACM_EP0MAXPACKET=64 +CONFIG_CDCACM_EPINTIN=1 +CONFIG_CDCACM_EPINTIN_FSSIZE=64 +CONFIG_CDCACM_EPINTIN_HSSIZE=64 +CONFIG_CDCACM_EPBULKOUT=3 +CONFIG_CDCACM_EPBULKOUT_FSSIZE=64 +CONFIG_CDCACM_EPBULKOUT_HSSIZE=512 +CONFIG_CDCACM_EPBULKIN=2 +CONFIG_CDCACM_EPBULKIN_FSSIZE=64 +CONFIG_CDCACM_EPBULKIN_HSSIZE=512 +CONFIG_CDCACM_NRDREQS=4 +CONFIG_CDCACM_NWRREQS=4 +CONFIG_CDCACM_BULKIN_REQLEN=96 +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=4000 +CONFIG_CDCACM_VENDORID=0x26ac +CONFIG_CDCACM_PRODUCTID=0x0013 +CONFIG_CDCACM_VENDORSTR="3D Robotics" +CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v4.x PRO" +# CONFIG_USBMSC is not set +# CONFIG_USBHOST is not set +# CONFIG_HAVE_USBTRACE is not set +# CONFIG_DRIVERS_WIRELESS is not set +# CONFIG_DRIVERS_CONTACTLESS is not set + +# +# System Logging +# +# CONFIG_ARCH_SYSLOG is not set +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_INTBUFFER is not set +# CONFIG_SYSLOG_TIMESTAMP is not set +CONFIG_SYSLOG_SERIAL_CONSOLE=y +# CONFIG_SYSLOG_CHAR is not set +CONFIG_SYSLOG_CONSOLE=y +# CONFIG_SYSLOG_NONE is not set +# CONFIG_SYSLOG_FILE is not set +# CONFIG_SYSLOG_CHARDEV is not set + +# +# Networking Support +# +# CONFIG_ARCH_HAVE_NET is not set +# CONFIG_ARCH_HAVE_PHY is not set +# CONFIG_NET is not set + +# +# Crypto API +# +# CONFIG_CRYPTO is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_AUTOMOUNTER is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +CONFIG_FS_READABLE=y +CONFIG_FS_WRITABLE=y +# CONFIG_FS_AIO is not set +# CONFIG_FS_NAMED_SEMAPHORES is not set +CONFIG_FS_MQUEUE_MPATH="/var/mqueue" +# CONFIG_FS_RAMMAP is not set +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +CONFIG_FS_FATTIME=y +# CONFIG_FAT_FORCE_INDIRECT is not set +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_DIRECT_RETRY=y +# CONFIG_FS_NXFFS is not set +CONFIG_FS_ROMFS=y +# CONFIG_FS_TMPFS is not set +# CONFIG_FS_SMARTFS is not set +CONFIG_FS_BINFS=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_REGISTER=y + +# +# Exclude individual procfs entries +# +# CONFIG_FS_PROCFS_EXCLUDE_PROCESS is not set +# CONFIG_FS_PROCFS_EXCLUDE_UPTIME is not set +# CONFIG_FS_PROCFS_EXCLUDE_MOUNTS is not set +# CONFIG_FS_PROCFS_EXCLUDE_MTD is not set +# CONFIG_FS_PROCFS_EXCLUDE_PARTITIONS is not set +# CONFIG_FS_UNIONFS is not set + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_ARCH_HAVE_HEAP2 is not set +CONFIG_GRAN=y +# CONFIG_GRAN_SINGLE is not set +CONFIG_GRAN_INTR=y + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# + +# +# Binary Loader +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_NOPRINTF_FIELDWIDTH is not set +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_IOCTL_VARIADIC is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set +CONFIG_LIB_RAND_ORDER=1 +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 +CONFIG_LIBC_STRERROR=y +# CONFIG_LIBC_STRERROR_SHORT is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_LIBC_TMPDIR="/tmp" +CONFIG_LIBC_MAX_TMPFILE=32 +CONFIG_ARCH_LOWPUTC=y +# CONFIG_LIBC_LOCALTIME is not set +CONFIG_TIME_EXTENDED=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y +CONFIG_ARCH_MEMCPY=y +# CONFIG_ARCH_MEMCMP is not set +# CONFIG_ARCH_MEMMOVE is not set +# CONFIG_ARCH_MEMSET is not set +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_ARCH_STRCHR is not set +# CONFIG_ARCH_STRCMP is not set +# CONFIG_ARCH_STRCPY is not set +# CONFIG_ARCH_STRNCPY is not set +# CONFIG_ARCH_STRLEN is not set +# CONFIG_ARCH_STRNLEN is not set +# CONFIG_ARCH_BZERO is not set +CONFIG_ARCH_HAVE_TLS=y +# CONFIG_TLS is not set +# CONFIG_LIBC_NETDB is not set +# CONFIG_NETDB_HOSTFILE is not set + +# +# Non-standard Library Support +# +# CONFIG_LIB_CRC64_FAST is not set +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set +# CONFIG_LIB_HEX2BIN is not set + +# +# Basic CXX Support +# +CONFIG_C99_BOOL8=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# CAN Utilities +# +# CONFIG_CANUTILS_LIBUAVCAN is not set + +# +# Examples +# +# CONFIG_EXAMPLES_CCTYPE is not set +# CONFIG_EXAMPLES_CHAT is not set +# CONFIG_EXAMPLES_CONFIGDATA is not set +# CONFIG_EXAMPLES_CPUHOG is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FSTEST is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +CONFIG_EXAMPLES_MOUNT=y +# CONFIG_EXAMPLES_MOUNT_BLOCKDEVICE is not set +CONFIG_EXAMPLES_MOUNT_NSECTORS=2048 +CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512 +CONFIG_EXAMPLES_MOUNT_RAMDEVNO=0 +# CONFIG_EXAMPLES_MTDPART is not set +# CONFIG_EXAMPLES_NRF24L01TERM is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTERM is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PCA9635 is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERIALBLASTER is not set +# CONFIG_EXAMPLES_SERIALRX is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMP is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UNIONFS is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set + +# +# File System Utilities +# +# CONFIG_FSUTILS_FLASH_ERASEALL is not set +# CONFIG_FSUTILS_INIFILE is not set +# CONFIG_FSUTILS_PASSWD is not set + +# +# GPS Utilities +# +# CONFIG_GPSUTILS_MINMEA_LIB is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set +# CONFIG_GRAPHICS_TRAVELER is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_BAS is not set +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_MICROPYTHON is not set +# CONFIG_INTERPRETERS_MINIBASIC is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# Network Utilities +# +# CONFIG_NETUTILS_CHAT is not set +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_ESP8266 is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_THTTPD is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +# CONFIG_NSH_MOTD is not set + +# +# Command Line Configuration +# +CONFIG_NSH_READLINE=y +# CONFIG_NSH_CLE is not set +CONFIG_NSH_LINELEN=128 +# CONFIG_NSH_DISABLE_SEMICOLON is not set +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_MAXARGUMENTS=12 +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_NESTDEPTH=8 +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_ADDROUTE is not set +# CONFIG_NSH_DISABLE_BASENAME is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_CMP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_DELROUTE is not set +# CONFIG_NSH_DISABLE_DIRNAME is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_PRINTF is not set +# CONFIG_NSH_DISABLE_PS is not set +CONFIG_NSH_DISABLE_PSSTACKUSAGE=y +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNAME is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +CONFIG_NSH_PROC_MOUNTPOINT="/proc" +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_STRERROR=y + +# +# Scripting Support +# +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +CONFIG_NSH_ROMFSETC=y +# CONFIG_NSH_ROMFSRC is not set +CONFIG_NSH_ROMFSMOUNTPT="/etc" +CONFIG_NSH_INITSCRIPT="init.d/rcS" +CONFIG_NSH_ROMFSDEVNO=0 +CONFIG_NSH_ROMFSSECTSIZE=128 +# CONFIG_NSH_DEFAULTROMFS is not set +CONFIG_NSH_ARCHROMFS=y +# CONFIG_NSH_CUSTOMROMFS is not set +CONFIG_NSH_FATDEVNO=1 +CONFIG_NSH_FATSECTSIZE=512 +CONFIG_NSH_FATNSECTORS=1024 +CONFIG_NSH_FATMOUNTPT="/tmp" + +# +# Console Configuration +# +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_USBCONSOLE is not set +# CONFIG_NSH_ALTCONDEV is not set +CONFIG_NSH_ARCHINIT=y +# CONFIG_NSH_LOGIN is not set +# CONFIG_NSH_CONSOLE_LOGIN is not set + +# +# NxWidgets/NxWM +# + +# +# Platform-specific Support +# +# CONFIG_PLATFORM_CONFIGDATA is not set + +# +# System Libraries and NSH Add-Ons +# +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_CDCACM_DEVMINOR=0 +# CONFIG_SYSTEM_CLE is not set +CONFIG_SYSTEM_CUTERM=y +CONFIG_SYSTEM_CUTERM_DEFAULT_DEVICE="/dev/ttyS0" +CONFIG_SYSTEM_CUTERM_DEFAULT_BAUD=57600 +CONFIG_SYSTEM_CUTERM_STACKSIZE=2048 +CONFIG_SYSTEM_CUTERM_PRIORITY=100 +# CONFIG_SYSTEM_FLASH_ERASEALL is not set +# CONFIG_SYSTEM_FREE is not set +# CONFIG_SYSTEM_HEX2BIN is not set +# CONFIG_SYSTEM_HEXED is not set +# CONFIG_SYSTEM_I2CTOOL is not set +# CONFIG_SYSTEM_INSTALL is not set +# CONFIG_SYSTEM_RAMTEST is not set +CONFIG_READLINE_HAVE_EXTMATCH=y +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y +# CONFIG_READLINE_TABCOMPLETION is not set +# CONFIG_READLINE_CMD_HISTORY is not set +# CONFIG_SYSTEM_STACKMONITOR is not set +# CONFIG_SYSTEM_SUDOKU is not set +# CONFIG_SYSTEM_SYSTEM is not set +# CONFIG_SYSTEM_TEE is not set +# CONFIG_SYSTEM_UBLOXMODEM is not set +# CONFIG_SYSTEM_VI is not set +# CONFIG_SYSTEM_ZMODEM is not set diff --git a/nuttx-configs/px4fmu-v4pro/nsh/setenv.sh b/nuttx-configs/px4fmu-v4pro/nsh/setenv.sh new file mode 100644 index 0000000000..265520997d --- /dev/null +++ b/nuttx-configs/px4fmu-v4pro/nsh/setenv.sh @@ -0,0 +1,67 @@ +#!/bin/bash +# configs/stm3240g-eval/nsh/setenv.sh +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This 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" + +# This the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/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}" diff --git a/nuttx-configs/px4fmu-v4pro/scripts/ld.script b/nuttx-configs/px4fmu-v4pro/scripts/ld.script new file mode 100644 index 0000000000..d83d744876 --- /dev/null +++ b/nuttx-configs/px4fmu-v4pro/scripts/ld.script @@ -0,0 +1,158 @@ +/**************************************************************************** + * configs/px4fmu-v4pro/common/ld.script + * + * Copyright (C) 2011, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 STM32F469II has 2048Kb of FLASH beginning at address 0x0800:0000 and + * 384Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 160Kb of SRAM beginning at address 0x2000:0000 + * 2) 32Kb of SRAM beginning at address 0x2002:8000 + * 3) 128Kb of SRAM beginning at address 0x2003:0000 + * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The first 0x4000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 320K + ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * 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.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + /* + * This is a hack to make the newlib libm __errno() call + * use the NuttX get_errno_ptr() function. + */ + __errno = get_errno_ptr; + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + /* + * Construction data for parameters. + */ + __param ALIGN(4): { + __param_start = ABSOLUTE(.); + KEEP(*(__param*)) + __param_end = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx-configs/px4fmu-v4pro/src/Makefile b/nuttx-configs/px4fmu-v4pro/src/Makefile new file mode 100644 index 0000000000..bf9088501f --- /dev/null +++ b/nuttx-configs/px4fmu-v4pro/src/Makefile @@ -0,0 +1,88 @@ +############################################################################ +# configs/px4fmu-v4pro/src/Makefile +# +# Copyright (C) 2011, 2016 Gregory Nutt. All rights reserved. +# Authors: Gregory Nutt +# David Sidrane +# +# 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 diff --git a/nuttx-configs/px4fmu-v4pro/src/empty.c b/nuttx-configs/px4fmu-v4pro/src/empty.c new file mode 100644 index 0000000000..5de10699fb --- /dev/null +++ b/nuttx-configs/px4fmu-v4pro/src/empty.c @@ -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. + */ diff --git a/src/drivers/boards/px4fmu-v4pro/CMakeLists.txt b/src/drivers/boards/px4fmu-v4pro/CMakeLists.txt new file mode 100644 index 0000000000..1633310485 --- /dev/null +++ b/src/drivers/boards/px4fmu-v4pro/CMakeLists.txt @@ -0,0 +1,48 @@ +############################################################################ +# +# Copyright (c) 2015 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__px4fmu-v4pro + COMPILE_FLAGS + SRCS + ../common/board_name.c + ../common/board_dma_alloc.c + px4fmu_can.c + px4fmu_init.c + px4fmu_timer_config.c + px4fmu_spi.c + px4fmu_usb.c + px4fmu_led.c + DEPENDS + platforms__common + ) +# vim: set noet ft=cmake fenc=utf-8 ff=unix : diff --git a/src/drivers/boards/px4fmu-v4pro/board_config.h b/src/drivers/boards/px4fmu-v4pro/board_config.h new file mode 100644 index 0000000000..9d9212ddf7 --- /dev/null +++ b/src/drivers/boards/px4fmu-v4pro/board_config.h @@ -0,0 +1,388 @@ +/**************************************************************************** + * + * Copyright (c) 2013-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 + * + * PX4FMUv2 internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +__BEGIN_DECLS + +/* these headers are not C++ safe */ +#include +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +/* PX4IO connection configuration */ +#define PX4IO_SERIAL_DEVICE "/dev/ttyS4" +#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX +#define PX4IO_SERIAL_BASE STM32_USART6_BASE /* hardwired on the board */ +#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX_2 +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX_2 +#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + +/* 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 */ + +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN11) +#define GPIO_LED2 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1) +#define GPIO_LED3 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN3) + +#define GPIO_LED_RED GPIO_LED1 +#define GPIO_LED_GREEN GPIO_LED2 +#define GPIO_LED_BLUE GPIO_LED3 + +/* Define the Chip Selects */ + +/* SPI Bus 1 Internal Sensors */ + +#define GPIO_SPI_CS_MPU9250 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2) +#define GPIO_SPI_CS_LIS3MDL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15) +#define GPIO_SPI_CS_MS5611 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) +#define GPIO_SPI_CS_ICM_20608_G (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) + +/* SPI Bus 2 Memory */ + +#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) + +/* Aux Chip selects (not pined out on RC0 HW) */ + +#define GPIO_AUX_CS0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN10) +#define GPIO_AUX_CS1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN11) +#define GPIO_AUX_CS2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN12) +#define GPIO_AUX_CS3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN13) +#define GPIO_AUX_CS4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN14) +#define GPIO_AUX_CS5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN15) + + +/* External Chip selects on Connectors ahead PAD3 */ + +#define GPIO_SPI5_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN6) +#define GPIO_SPI6_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN11) + +/* Define the Ready interrupts */ + +#define GPIO_DRDY_MPU9250 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) +#define GPIO_DRDY_LIS3MDL (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN12) +#define GPIO_DRDY_ICM_20608_G (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) + + +/* + * 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_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_LIS3MDL _PIN_OFF(GPIO_DRDY_LIS3MDL) +#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) + +#define PX4_SPI_BUS_SENSORS 1 +#define PX4_SPI_BUS_RAMTRON 2 +#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS +#define PX4_SPI_EXT0 5 +#define PX4_SPI_EXT1 6 + +/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */ + +#define PX4_SPIDEV_GYRO 1 +#define PX4_SPIDEV_ACCEL_MAG 2 +#define PX4_SPIDEV_BARO 3 +#define PX4_SPIDEV_MPU 4 +#define PX4_SPIDEV_HMC 5 +#define PX4_SPIDEV_ICM 6 +#define PX4_SPIDEV_LIS 7 +#define PX4_SPIDEV_BMI 8 +#define PX4_SPIDEV_BMA 9 +#define PX4_SPIDEV_EXT0 10 +#define PX4_SPIDEV_EXT1 11 + + +/* I2C busses */ +#define PX4_I2C_BUS_ONBOARD 1 +#define PX4_I2C_BUS_EXPANSION 2 +#define PX4_I2C_BUS_LED PX4_I2C_BUS_ONBOARD + +/* 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 << 2) | (1 << 3) | (1 << 4) | (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 2 +#define ADC_BATTERY_CURRENT_CHANNEL 3 +//#define ADC_BATTERY_VOLTAGE_CHANNEL2 4 +//#define ADC_BATTERY_CURRENT_CHANNEL2 5 +#define ADC_5V_RAIL_SENSE 4 +#define ADC_RC_RSSI_CHANNEL 11 + +/* User GPIOs + * + * GPIO0-5 are the PWM servo outputs. + */ +#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN14) +#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN13) +#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) +#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN9) +#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13) +#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14) + +#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14) +#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13) +#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) +#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) +#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) +#define GPIO_GPIO5_OUTPUT (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 (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5) +#define GPIO_VDD_BRICK2_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN5) +#define GPIO_VDD_3V3_SENSORS_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +#define GPIO_VDD_3V3_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5) +#define GPIO_VDD_5V_PERIPH_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_5V_RC_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN3) +#define GPIO_VBUS_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0) + +/* Tone alarm output */ +#define TONE_ALARM_TIMER 2 /* timer 2 */ +#define TONE_ALARM_CHANNEL 1 /* channel 1 */ +#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) + +/* 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 (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN9) +#define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11) +#define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13) +#define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14) +#define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN13) +#define GPIO_TIM4_CH3OUT (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 GPIO_TIM1_CH1IN_2 +#define GPIO_TIM1_CH2IN GPIO_TIM1_CH2IN_2 +#define GPIO_TIM1_CH3IN GPIO_TIM1_CH3IN_2 +#define GPIO_TIM1_CH4IN GPIO_TIM1_CH4IN_2 +#define GPIO_TIM4_CH2IN GPIO_TIM4_CH2IN_2 +#define GPIO_TIM4_CH3IN GPIO_TIM4_CH3IN_2 +#define DIRECT_INPUT_TIMER_CHANNELS 6 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 3 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel */ + +#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 2 */ +#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF2|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0) + +//#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 2 +#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2 + +#define GPIO_RSSI_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1) +#define GPIO_LED_SAFETY (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN3) +#define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4) +//#define GPIO_PERIPH_3V3_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5) +/* for R12, this signal is active high */ +#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13) +#define INVERT_RC_INPUT(_s) px4_arch_gpiowrite(GPIO_SBUS_INV, _s) + +#define GPIO_8266_GPIO0 (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN2) +//TODO:VET#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4) +#define GPIO_8266_PD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) +#define GPIO_8266_RST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN6) + +/* 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-pro has a separate GPIO for serial RC output +#define GPIO_RC_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0) +#define SPEKTRUM_RX_AS_GPIO() px4_arch_configgpio(GPIO_RC_OUT) +#define SPEKTRUM_RX_HIGH(_s) px4_arch_gpiowrite(GPIO_RC_OUT, (_s)) + + +#define BOARD_NAME "PX4FMU_V4PRO" + +/* 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_BRICK2_VALID (px4_arch_gpioread(GPIO_VDD_BRICK2_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_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); +void board_spi_reset(int ms); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + + +/**************************************************************************** + * Name: nsh_archinitialize + * + * Description: + * Perform architecture specific initialization for NSH. + * + * CONFIG_NSH_ARCHINIT=y : + * Called from the NSH library + * + * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, && + * CONFIG_NSH_ARCHINIT=n : + * Called from board_initialize(). + * + ****************************************************************************/ + +#ifdef CONFIG_NSH_LIBRARY +int nsh_archinitialize(void); +#endif + +#include "../common/board_common.h" + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/src/drivers/boards/px4fmu-v4pro/px4fmu_can.c b/src/drivers/boards/px4fmu-v4pro/px4fmu_can.c new file mode 100644 index 0000000000..7ac775ae64 --- /dev/null +++ b/src/drivers/boards/px4fmu-v4pro/px4fmu_can.c @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4fmu_can.c + * + * Board-specific CAN functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" + +#include "stm32.h" +#include "stm32_can.h" +#include "board_config.h" + +#ifdef CONFIG_CAN + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif diff --git a/src/drivers/boards/px4fmu-v4pro/px4fmu_init.c b/src/drivers/boards/px4fmu-v4pro/px4fmu_init.c new file mode 100644 index 0000000000..6983132cee --- /dev/null +++ b/src/drivers/boards/px4fmu-v4pro/px4fmu_init.c @@ -0,0 +1,674 @@ +/**************************************************************************** + * + * 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 px4fmu_init.c + * + * PX4FMU-specific early startup code. This file implements the + * nsh_archinitialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialisation. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include "board_config.h" +#include + +#include + +#include +#include + +#include +#include +#include +#include + +#include + +#include + +/**************************************************************************** + * 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_VDD_3V3_PERIPH_EN); + + stm32_gpiowrite(GPIO_VDD_3V3_PERIPH_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_VDD_3V3_PERIPH_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 */ + //todo:Revisit! ADC3 etc + 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_VDD_3V3_PERIPH_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(); + + stm32_usbinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +static struct spi_dev_s *spi1; +static struct spi_dev_s *spi2; +static struct spi_dev_s *spi5; +static struct spi_dev_s *spi6; +static struct sdio_dev_s *sdio; + +__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); + + /* Configure SPI-based devices */ + + spi1 = stm32_spibus_initialize(PX4_SPI_BUS_SENSORS); + + if (!spi1) { + message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS); + board_autoled_on(LED_RED); + return -ENODEV; + } + + /* Default SPI1 to 1MHz and de-assert the known chip selects. */ + SPI_SETFREQUENCY(spi1, 10000000); + SPI_SETBITS(spi1, 8); + SPI_SETMODE(spi1, SPIDEV_MODE3); + SPI_SELECT(spi1, PX4_SPIDEV_ICM, false); + SPI_SELECT(spi1, PX4_SPIDEV_BARO, false); + SPI_SELECT(spi1, PX4_SPIDEV_LIS, false); + SPI_SELECT(spi1, PX4_SPIDEV_MPU, false); + up_udelay(20); + + /* Get the SPI port for the FRAM */ + + spi2 = stm32_spibus_initialize(PX4_SPI_BUS_RAMTRON); + + if (!spi2) { + message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON); + board_autoled_on(LED_RED); + return -ENODEV; + } + + /* Default SPI2 to 12MHz and de-assert the known chip selects. + */ + + // XXX start with 10.4 MHz and go up to 20 once validated + SPI_SETFREQUENCY(spi2, 20 * 1000 * 1000); + SPI_SETBITS(spi2, 8); + SPI_SETMODE(spi2, SPIDEV_MODE3); + SPI_SELECT(spi2, SPIDEV_FLASH, false); + + /* Configure SPI 5-based devices */ + + spi5 = stm32_spibus_initialize(PX4_SPI_EXT0); + + if (!spi5) { + message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_EXT0); + board_autoled_on(LED_RED); + return -ENODEV; + } + + /* Default SPI5 to 1MHz and de-assert the known chip selects. */ + SPI_SETFREQUENCY(spi5, 10000000); + SPI_SETBITS(spi5, 8); + SPI_SETMODE(spi5, SPIDEV_MODE3); + SPI_SELECT(spi5, PX4_SPIDEV_EXT0, false); + + /* Configure SPI 6-based devices */ + + spi6 = stm32_spibus_initialize(PX4_SPI_EXT1); + + if (!spi6) { + message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_EXT1); + board_autoled_on(LED_RED); + return -ENODEV; + } + + /* Default SPI6 to 1MHz and de-assert the known chip selects. */ + SPI_SETFREQUENCY(spi6, 10000000); + SPI_SETBITS(spi6, 8); + SPI_SETMODE(spi6, SPIDEV_MODE3); + SPI_SELECT(spi6, PX4_SPIDEV_EXT1, false); + +#ifdef CONFIG_MMCSD + /* First, get an instance of the SDIO interface */ + + sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO); + + if (!sdio) { + message("[boot] Failed to initialize SDIO slot %d\n", + CONFIG_NSH_MMCSDSLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio); + + if (ret != OK) { + message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + /* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */ + sdio_mediachange(sdio, true); + +#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 +} diff --git a/src/drivers/boards/px4fmu-v4pro/px4fmu_led.c b/src/drivers/boards/px4fmu-v4pro/px4fmu_led.c new file mode 100644 index 0000000000..ddb34e8a56 --- /dev/null +++ b/src/drivers/boards/px4fmu-v4pro/px4fmu_led.c @@ -0,0 +1,106 @@ +/**************************************************************************** + * + * 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 + +#include + +#include "stm32.h" +#include "board_config.h" + +#include + +/* + * 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 + + + +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 +}; + +__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) +{ + /* Pull Down 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(led, true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(led, false); +} + +__EXPORT void led_toggle(int led) +{ + + phy_set_led(led, !phy_get_led(led)); +} diff --git a/src/drivers/boards/px4fmu-v4pro/px4fmu_spi.c b/src/drivers/boards/px4fmu-v4pro/px4fmu_spi.c new file mode 100644 index 0000000000..0b6341f974 --- /dev/null +++ b/src/drivers/boards/px4fmu-v4pro/px4fmu_spi.c @@ -0,0 +1,263 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4fmu_spi.c + * + * Board-specific SPI functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include "board_config.h" +#include + +/************************************************************************************ + * 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_STM32_SPI1 + stm32_configgpio(GPIO_SPI_CS_MPU9250); + stm32_configgpio(GPIO_SPI_CS_LIS3MDL); + stm32_configgpio(GPIO_SPI_CS_MS5611); + stm32_configgpio(GPIO_SPI_CS_ICM_20608_G); + + stm32_configgpio(GPIO_DRDY_MPU9250); + stm32_configgpio(GPIO_DRDY_LIS3MDL); + stm32_configgpio(GPIO_DRDY_ICM_20608_G); +#endif + +#ifdef CONFIG_STM32_SPI2 + stm32_configgpio(GPIO_SPI_CS_FRAM); +#endif +#ifdef CONFIG_STM32_SPI5 + stm32_configgpio(GPIO_SPI5_CS); +#endif +#ifdef CONFIG_STM32_SPI6 + stm32_configgpio(GPIO_SPI6_CS); +#endif + +} + +__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 */ + + switch (devid) { + case PX4_SPIDEV_ICM: + /* Making sure the other peripherals are not selected */ + stm32_gpiowrite(GPIO_SPI_CS_MPU9250, 1); + stm32_gpiowrite(GPIO_SPI_CS_LIS3MDL, 1); + stm32_gpiowrite(GPIO_SPI_CS_MS5611, 1); + stm32_gpiowrite(GPIO_SPI_CS_ICM_20608_G, !selected); + break; + + case PX4_SPIDEV_BARO: + /* Making sure the other peripherals are not selected */ + stm32_gpiowrite(GPIO_SPI_CS_MPU9250, 1); + stm32_gpiowrite(GPIO_SPI_CS_LIS3MDL, 1); + stm32_gpiowrite(GPIO_SPI_CS_MS5611, !selected); + stm32_gpiowrite(GPIO_SPI_CS_ICM_20608_G, 1); + break; + + case PX4_SPIDEV_LIS: + /* Making sure the other peripherals are not selected */ + stm32_gpiowrite(GPIO_SPI_CS_MPU9250, 1); + stm32_gpiowrite(GPIO_SPI_CS_LIS3MDL, !selected); + stm32_gpiowrite(GPIO_SPI_CS_MS5611, 1); + stm32_gpiowrite(GPIO_SPI_CS_ICM_20608_G, 1); + break; + + case PX4_SPIDEV_MPU: + /* Making sure the other peripherals are not selected */ + stm32_gpiowrite(GPIO_SPI_CS_MPU9250, !selected); + stm32_gpiowrite(GPIO_SPI_CS_LIS3MDL, 1); + stm32_gpiowrite(GPIO_SPI_CS_MS5611, 1); + stm32_gpiowrite(GPIO_SPI_CS_ICM_20608_G, 1); + break; + + default: + break; + } +} + +__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + return SPI_STATUS_PRESENT; +} + + +#ifdef CONFIG_STM32_SPI2 +__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + stm32_gpiowrite(GPIO_SPI_CS_FRAM, !selected); +} + +__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + /* FRAM is always present */ + return SPI_STATUS_PRESENT; +} +#endif + +/************************************************************************************ + * Name: stm32_spi5select and stm32_spi5status + * + * Description: + * Called by stm32 spi driver on bus 5. + * + ************************************************************************************/ + +#ifdef CONFIG_STM32_SPI5 +__EXPORT void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + stm32_gpiowrite(GPIO_SPI5_CS, !selected); + +} + +__EXPORT uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + return SPI_STATUS_PRESENT; +} +#endif + +/************************************************************************************ + * Name: stm32_spi6select and stm32_spi6status + * + * Description: + * Called by stm32 spi driver on bus 6. + * + ************************************************************************************/ + +#ifdef CONFIG_STM32_SPI6 +__EXPORT void stm32_spi6select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + stm32_gpiowrite(GPIO_SPI6_CS, !selected); + +} + +__EXPORT uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + return SPI_STATUS_PRESENT; +} +#endif + +__EXPORT void board_spi_reset(int ms) +{ + /* disable SPI bus */ + stm32_configgpio(GPIO_SPI_CS_OFF_MPU9250); + stm32_configgpio(GPIO_SPI_CS_OFF_LIS3MDL); + 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_LIS3MDL, 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_LIS3MDL); + stm32_configgpio(GPIO_DRDY_OFF_ICM_20608_G); + + stm32_gpiowrite(GPIO_DRDY_OFF_MPU9250, 0); + stm32_gpiowrite(GPIO_DRDY_OFF_LIS3MDL, 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_STM32_SPI1 + stm32_configgpio(GPIO_SPI_CS_MPU9250); + stm32_configgpio(GPIO_SPI_CS_LIS3MDL); + stm32_configgpio(GPIO_SPI_CS_MS5611); + stm32_configgpio(GPIO_SPI_CS_ICM_20608_G); + + stm32_configgpio(GPIO_SPI1_SCK); + stm32_configgpio(GPIO_SPI1_MISO); + stm32_configgpio(GPIO_SPI1_MOSI); + + /* bring up the EXTI pins again */ + stm32_configgpio(GPIO_DRDY_MPU9250); + stm32_configgpio(GPIO_DRDY_LIS3MDL); + stm32_configgpio(GPIO_DRDY_ICM_20608_G); + +#endif + +} diff --git a/src/drivers/boards/px4fmu-v4pro/px4fmu_timer_config.c b/src/drivers/boards/px4fmu-v4pro/px4fmu_timer_config.c new file mode 100644 index 0000000000..c2a778b793 --- /dev/null +++ b/src/drivers/boards/px4fmu-v4pro/px4fmu_timer_config.c @@ -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 px4fmu_timer_config.c + * + * Configuration data for the stm32 pwm_servo, input capture and pwm input driver. + * + * Note that these arrays must always be fully-sized. + */ + +#include + +#include +#include +#include + +#include +#include + +#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 + } +}; diff --git a/src/drivers/boards/px4fmu-v4pro/px4fmu_usb.c b/src/drivers/boards/px4fmu-v4pro/px4fmu_usb.c new file mode 100644 index 0000000000..4b455309db --- /dev/null +++ b/src/drivers/boards/px4fmu-v4pro/px4fmu_usb.c @@ -0,0 +1,107 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4fmu_usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#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_STM32_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); + /* XXX We only support device mode + stm32_configgpio(GPIO_OTGFS_PWRON); + stm32_configgpio(GPIO_OTGFS_OVER); + */ +#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); +}