From f754d092f849705c86c3e9146fed9bad8e7e4668 Mon Sep 17 00:00:00 2001 From: nathan Date: Tue, 27 Mar 2018 19:01:20 -0700 Subject: [PATCH] Initial omnibusf4sd target support Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766 NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup. Working: - mpu6000, bench tested and verified via nsh - fmu - all 6 ch output bench tested w/ pwm and oneshot via nsh - ppm input bench tested - dsm input bench tested - bmp280, bench tested and verified via nsh - hmc5883, bench tested and verified via nsh, but requires an external i2c pullup - gps on uart6 - startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud) - rgbled over i2c, bench tested and workingp - sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use Not yet implemented: - ADC - OSD: passthrough video is untested, use at your own risk until a basic driver is implemented. --- Jenkinsfile | 2 +- ROMFS/px4fmu_common/init.d/rc.interface | 2 +- ROMFS/px4fmu_common/init.d/rc.sensors | 12 +- ROMFS/px4fmu_common/init.d/rcS | 22 +- .../configs/nuttx_omnibus-f4sd_default.cmake | 150 ++ platforms/nuttx/Images/omnibus-f4sd.prototype | 13 + .../omnibus-f4sd/include/board.h | 398 ++++ .../omnibus-f4sd/include/nsh_romfsimg.h | 42 + .../nuttx-configs/omnibus-f4sd/nsh/defconfig | 1627 +++++++++++++++++ .../omnibus-f4sd/scripts/ld.script | 150 ++ src/drivers/barometer/bmp280/bmp280.cpp | 6 +- src/drivers/boards/common/board_dma_alloc.c | 2 +- .../boards/omnibus-f4sd/CMakeLists.txt | 49 + .../boards/omnibus-f4sd/board_config.h | 340 ++++ src/drivers/boards/omnibus-f4sd/init.c | 507 +++++ src/drivers/boards/omnibus-f4sd/led.c | 125 ++ src/drivers/boards/omnibus-f4sd/spi.c | 184 ++ .../boards/omnibus-f4sd/timer_config.c | 120 ++ src/drivers/boards/omnibus-f4sd/usb.c | 108 ++ src/drivers/px4fmu/fmu.cpp | 2 + 20 files changed, 3850 insertions(+), 11 deletions(-) create mode 100644 cmake/configs/nuttx_omnibus-f4sd_default.cmake create mode 100644 platforms/nuttx/Images/omnibus-f4sd.prototype create mode 100644 platforms/nuttx/nuttx-configs/omnibus-f4sd/include/board.h create mode 100644 platforms/nuttx/nuttx-configs/omnibus-f4sd/include/nsh_romfsimg.h create mode 100644 platforms/nuttx/nuttx-configs/omnibus-f4sd/nsh/defconfig create mode 100644 platforms/nuttx/nuttx-configs/omnibus-f4sd/scripts/ld.script create mode 100644 src/drivers/boards/omnibus-f4sd/CMakeLists.txt create mode 100644 src/drivers/boards/omnibus-f4sd/board_config.h create mode 100644 src/drivers/boards/omnibus-f4sd/init.c create mode 100644 src/drivers/boards/omnibus-f4sd/led.c create mode 100644 src/drivers/boards/omnibus-f4sd/spi.c create mode 100644 src/drivers/boards/omnibus-f4sd/timer_config.c create mode 100644 src/drivers/boards/omnibus-f4sd/usb.c diff --git a/Jenkinsfile b/Jenkinsfile index 427d948584..fe42ac87e6 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -53,7 +53,7 @@ pipeline { } // nuttx default targets that are archived and uploaded to s3 - for (def option in ["px4fmu-v4", "px4fmu-v4pro", "px4fmu-v5", "aerofc-v1", "aerocore2", "auav-x21", "crazyflie", "mindpx-v2", "nxphlite-v3", "tap-v1"]) { + for (def option in ["px4fmu-v4", "px4fmu-v4pro", "px4fmu-v5", "aerofc-v1", "aerocore2", "auav-x21", "crazyflie", "mindpx-v2", "nxphlite-v3", "tap-v1", "omnibus-f4sd"]) { def node_name = "${option}" builds[node_name] = createBuildNode(docker_nuttx, "${node_name}_default") } diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index 4afd58fa4c..15859d2301 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -120,7 +120,7 @@ then fi fi -if ver hwcmp MINDPX_V2 CRAZYFLIE AEROFC_V1 PX4FMU_V4 NXPHLITE_V3 +if ver hwcmp MINDPX_V2 CRAZYFLIE AEROFC_V1 PX4FMU_V4 NXPHLITE_V3 OMNIBUS_F4SD then set MIXER_AUX none fi diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 7cac355f26..ede1115da8 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -3,7 +3,7 @@ # Standard startup script for sensor drivers. # -if ver hwcmp AEROFC_V1 +if ver hwcmp AEROFC_V1 OMNIBUS_F4SD then # Aero FC uses separate driver else @@ -267,6 +267,16 @@ then ll40ls start i2c fi +if ver hwcmp OMNIBUS_F4SD +then + mpu6000 -R 12 -s start + + # Possible external compasses + hmc5883 -X start + + bmp280 start +fi + if ver hwcmp PX4FMU_V4PRO then # Internal SPI bus ICM-20608-G diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index b64e58b538..9f53abd21e 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -13,6 +13,12 @@ set +e # # NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS. # +# UART mapping on OMNIBUSF4SD: +# +# USART1 /dev/ttyS0 SerialRX +# USART4 /dev/ttyS1 TELEM1 +# USART6 /dev/ttyS2 GPS +# # UART mapping on FMUv2/3/4: # # UART1 /dev/ttyS0 IO debug (except v4, there ttyS0 is the wifi) @@ -229,6 +235,11 @@ then set MAVLINK_COMPANION_DEVICE /dev/ttyS4 fi + if ver hwcmp OMNIBUS_F4SD + then + set MAVLINK_COMPANION_DEVICE /dev/ttyS1 + fi + # # Set USE_IO flag # @@ -281,8 +292,8 @@ then # if [ $AUTOCNF == yes ] then - # Disable safety switch by default on Pixracer - if ver hwcmp PX4FMU_V4 + # Disable safety switch by default on Pixracer and OmnibusF4SD + if ver hwcmp PX4FMU_V4 OMNIBUS_F4SD then param set CBRK_IO_SAFETY 22027 fi @@ -412,7 +423,6 @@ then sh /etc/init.d/rc.sensors commander start fi - send_event start load_mon start @@ -573,12 +583,12 @@ then fi fi - if ver hwcmp CRAZYFLIE + if ver hwcmp CRAZYFLIE OMNIBUS_F4SD then # Avoid using either of the two available serials set MAVLINK_F none fi - fi +fi if [ "x$MAVLINK_F" == xnone ] then @@ -707,7 +717,7 @@ then fi fi - if ver hwcmp PX4FMU_V2 PX4FMU_V4 PX4FMU_V4PRO MINDPX_V2 PX4FMU_V5 + if ver hwcmp PX4FMU_V2 PX4FMU_V4 PX4FMU_V4PRO MINDPX_V2 PX4FMU_V5 OMNIBUS_F4SD then # Check for flow sensor - as it is a background task, launch it last px4flow start & diff --git a/cmake/configs/nuttx_omnibus-f4sd_default.cmake b/cmake/configs/nuttx_omnibus-f4sd_default.cmake new file mode 100644 index 0000000000..d25168fa34 --- /dev/null +++ b/cmake/configs/nuttx_omnibus-f4sd_default.cmake @@ -0,0 +1,150 @@ + +px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common) + +set(config_uavcan_num_ifaces 1) + +set(config_module_list + # + # Board support modules + # + drivers/barometer/bmp280 + #drivers/differential_pressure + #drivers/distance_sensor + drivers/magnetometer/hmc5883 + drivers/telemetry/frsky_telemetry + drivers/imu/mpu6000 + + #drivers/batt_smbus + #drivers/blinkm + #drivers/camera_trigger + drivers/gps + #drivers/irlock + #drivers/mkblctrl + #drivers/oreoled + #drivers/pca9685 + #drivers/pwm_input + drivers/px4flow + drivers/px4fmu + drivers/rgbled + drivers/stm32 + #drivers/stm32/adc + #drivers/stm32/tone_alarm + #drivers/tap_esc + #drivers/vmount + modules/sensors + + # + # System commands + # + systemcmds/bl_update + systemcmds/config + #systemcmds/dumpfile + #systemcmds/esc_calib + systemcmds/hardfault_log + systemcmds/led_control + 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/tune_control + systemcmds/ver + + ## + ## Testing + ## + #drivers/distance_sensor/sf0x/sf0x_tests + #drivers/test_ppm + ##lib/rc/rc_tests + #modules/commander/commander_tests + #lib/controllib/controllib_test + #modules/mavlink/mavlink_tests + #modules/mc_pos_control/mc_pos_control_tests + #modules/uORB/uORB_tests + #systemcmds/tests + + # + # General system control + # + #modules/camera_feedback + modules/commander + modules/events + modules/gpio_led + modules/land_detector + modules/load_mon + modules/mavlink + modules/navigator + #modules/uavcan + + # + # Estimation modules + # + modules/attitude_estimator_q + modules/ekf2 + modules/landing_target_estimator + modules/local_position_estimator + #modules/position_estimator_inav + modules/wind_estimator + + # + # Vehicle Control + # + modules/fw_att_control + modules/fw_pos_control_l1 + modules/gnd_att_control + modules/gnd_pos_control + modules/mc_att_control + modules/mc_pos_control + modules/vtol_att_control + + # + # Logging + # + modules/logger + modules/sdlog2 + + # + # Library modules + # + modules/dataman + + ## + ## OBC challenge + ## + #examples/bottle_drop + + ## + ## Rover apps + ## + #examples/rover_steering_control + + ## + ## Segway + ## + #examples/segway + + ## + ## Demo apps + ## + + ## Tutorial code from + ## https://px4.io/dev/px4_simple_app + #examples/px4_simple_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 +) diff --git a/platforms/nuttx/Images/omnibus-f4sd.prototype b/platforms/nuttx/Images/omnibus-f4sd.prototype new file mode 100644 index 0000000000..c7f2421ac5 --- /dev/null +++ b/platforms/nuttx/Images/omnibus-f4sd.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 42, + "magic": "OMNIBUSF4SD", + "description": "Firmware for the OmnibusF4SD board", + "image": "", + "build_time": 0, + "summary": "PX4/OmnibusF4", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1032192, + "git_identity": "", + "board_revision": 0 +} diff --git a/platforms/nuttx/nuttx-configs/omnibus-f4sd/include/board.h b/platforms/nuttx/nuttx-configs/omnibus-f4sd/include/board.h new file mode 100644 index 0000000000..252427c48c --- /dev/null +++ b/platforms/nuttx/nuttx-configs/omnibus-f4sd/include/board.h @@ -0,0 +1,398 @@ +/************************************************************************************ + * nuttx-configs/omnibus-f4sd/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Copyright (c) 2018 PX4 Development Team. All rights reserved. + * Author: Nathan Tsoi + * + * 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 __CONFIG_OMNIBUSF4SD_INCLUDE_BOARD_H +#define __CONFIG_OMNIBUSF4SD_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdio.h" +#include "stm32.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The omnibusf4sd board features a single 8MHz crystal. Space is provided + * for a 32kHz RTC backup crystal, but it is not stuffed. + * + * This is the canonical configuration: + * System Clock source : PLL (HSE) + * SYSCLK(Hz) : 168000000 Determined by PLL configuration + * HCLK(Hz) : 168000000 (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) : 8000000 (STM32_BOARD_XTAL) + * PLLM : 8 (STM32_PLLCFG_PLLM) + * PLLN : 336 (STM32_PLLCFG_PLLN) + * PLLP : 2 (STM32_PLLCFG_PLLP) + * PLLQ : 7 (STM32_PLLCFG_PLLQ) + * 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, : Enabled + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - On-board crystal frequency is 8MHz + * LSE - 32.768 kHz + */ + +#define STM32_BOARD_XTAL 8000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * = (8,000,000 / 8) * 336 + * = 336,000,000 + * SYSCLK = PLL_VCO / PLLP + * = 336,000,000 / 2 = 168,000,000 + * USB OTG FS, SDIO and RNG Clock + * = PLL_VCO / PLLQ + * = 48,000,000 + */ + +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7) + +#define STM32_SYSCLK_FREQUENCY 168000000ul + +/* AHB clock (HCLK) is SYSCLK (168MHz) */ + +#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 (42MHz) */ + +#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 (84MHz) */ + +#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 + +/* SDIO 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, SDIO_CK=SDIOCLK/(118+2)=400 KHz + */ + +#define SDIO_INIT_CLKDIV (118 << SDIO_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_STM32_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, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_STM32_SDIO_DMA +# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA Channl/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 + +/* LED definitions ******************************************************************/ +/* 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 stm32_setled() */ + +#define BOARD_LED1 0 +//#define BOARD_LED2 1 +#define BOARD_NLEDS 1 + +#define BOARD_LED_BLUE BOARD_LED1 +//#define BOARD_LED_RED BOARD_LED2 + +/* LED bits for use with stm32_setleds() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) + +/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board the + * omnibusf4sd. The following definitions describe how NuttX controls the LEDs: + */ + +#define LED_STARTED 0 /* LED1 */ +#define LED_HEAPALLOCATE 1 /* LED2 */ +#define LED_IRQSENABLED 2 /* LED1 */ +#define LED_STACKCREATED 3 /* LED1 + LED2 */ +#define LED_INIRQ 4 /* LED1 */ +#define LED_SIGNAL 5 /* LED2 */ +#define LED_ASSERTION 6 /* LED1 + LED2 */ +#define LED_PANIC 7 /* LED1 + LED2 */ + +/* Alternate function pin selections ************************************************/ + +/* UART1: + * + * PA10 (RX) and PA9 (TX) are broken out on J5 + */ + +#define GPIO_USART1_RX GPIO_USART1_RX_1 +#define GPIO_USART1_TX GPIO_USART1_TX_1 + +/* USART1 require a RX DMA configuration */ +#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2 + +/* USART3: + * + * PC10 (TX) and PC11 (RX) are broken out on J4 + * + * However, this port is shared with SPI3 which contains the BMP280 and MAX7456 + * + * The Silkscreen pin labeled SCL is TX + * MISO is RX + */ +//#define GPIO_USART3_RX GPIO_USART3_RX_2 +//#define GPIO_USART3_TX GPIO_USART3_TX_2 + +/* UART4: + * + * PA0 (TX) -- Labeled RSSI on the silkscreen is only broken out on a test pad + * on the pro version. It's on a 2.54mm header on other versions + * PA1 (RX) -- Motor 5 out + */ +#define GPIO_UART4_RX GPIO_UART4_RX_1 +#define GPIO_UART4_TX GPIO_UART4_TX_1 + +/* UART6: + * + * PC6 (TX) and PC7 (RX) are broken out on J10 + */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 +#define GPIO_USART6_TX GPIO_USART6_TX_1 + +/* USART6 require a RX DMA configuration */ +#define DMAMAP_USART6_RX DMAMAP_USART6_RX_1 + +/* SPI1: + * MPU6000 + * CS: PA4 -- configured in board_config.h + * CLK: PA5 + * MISO: PA6 + * MOSI: PA7 + */ + +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 + +/* SPI2: + * SD Card + * CS: PB12 -- configured in board_config.h + * CLK: PB13 + * MISO: PB14 + * MOSI: PB15 + */ + +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 + +/* SPI3: + * BMP280 + * CS: PB3 -- configured in board_config.h + * CLK: PC10 + * MISO: PC11 + * MOSI: PC12 + */ + +#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2 +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_2 + +/* + * I2C (external) + * + * SCL: PB10 + * SDA: PB11 + * + * TODO: + * 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_I2C2_SCL GPIO_I2C2_SCL_1 +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 + +// TODO: +//#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN6) +//#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) + +/************************************************************************************ + * 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 intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +EXTERN void stm32_boardinitialize(void); + +/************************************************************************************ + * Name: stm32_ledinit, stm32_setled, and stm32_setleds + * + * Description: + * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If + * CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to + * control the LEDs from user applications. + * + ************************************************************************************/ + +#ifndef CONFIG_ARCH_LEDS +EXTERN void stm32_ledinit(void); +EXTERN void stm32_setled(int led, bool ledon); +EXTERN void stm32_setleds(uint8_t ledset); +#endif + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIG_OMNIBUSF4SD_INCLUDE_BOARD_H */ diff --git a/platforms/nuttx/nuttx-configs/omnibus-f4sd/include/nsh_romfsimg.h b/platforms/nuttx/nuttx-configs/omnibus-f4sd/include/nsh_romfsimg.h new file mode 100644 index 0000000000..a382a57fa6 --- /dev/null +++ b/platforms/nuttx/nuttx-configs/omnibus-f4sd/include/nsh_romfsimg.h @@ -0,0 +1,42 @@ +/**************************************************************************** + * + * Copyright (C) 2018 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * 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/platforms/nuttx/nuttx-configs/omnibus-f4sd/nsh/defconfig b/platforms/nuttx/nuttx-configs/omnibus-f4sd/nsh/defconfig new file mode 100644 index 0000000000..4220a9cbdc --- /dev/null +++ b/platforms/nuttx/nuttx-configs/omnibus-f4sd/nsh/defconfig @@ -0,0 +1,1627 @@ +# +# 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 +# CONFIG_DFU_BINARY 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_MISOC 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_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_LC823450 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_MOXART 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_STM32F0 is not set +# 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_XMC4 is not set +# CONFIG_ARCH_ARM7TDMI is not set +# CONFIG_ARCH_ARM920T is not set +# CONFIG_ARCH_ARM926EJS is not set +# CONFIG_ARCH_ARM1136J is not set +# CONFIG_ARCH_ARM1156T2 is not set +# CONFIG_ARCH_ARM1176JZ is not set +# CONFIG_ARCH_CORTEXM0 is not set +# CONFIG_ARCH_CORTEXM23 is not set +# CONFIG_ARCH_CORTEXM3 is not set +# CONFIG_ARCH_CORTEXM33 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_CORTEXR5F 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_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_TOOLCHAIN_CLANGL is not set +CONFIG_ARMV7M_HAVE_STACKCHECK=y +# CONFIG_ARMV7M_STACKCHECK is not set +# CONFIG_ARMV7M_ITMSYSLOG is not set +CONFIG_SERIAL_TERMIOS=y + +# +# 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_STM32L152CC is not set +# CONFIG_ARCH_CHIP_STM32L152RC is not set +# CONFIG_ARCH_CHIP_STM32L152VC 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_STM32F334K4 is not set +# CONFIG_ARCH_CHIP_STM32F334K6 is not set +# CONFIG_ARCH_CHIP_STM32F334K8 is not set +# CONFIG_ARCH_CHIP_STM32F334C4 is not set +# CONFIG_ARCH_CHIP_STM32F334C6 is not set +# CONFIG_ARCH_CHIP_STM32F334C8 is not set +# CONFIG_ARCH_CHIP_STM32F334R4 is not set +# CONFIG_ARCH_CHIP_STM32F334R6 is not set +# CONFIG_ARCH_CHIP_STM32F334R8 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_STM32F410RB is not set +# CONFIG_ARCH_CHIP_STM32F411RE is not set +# CONFIG_ARCH_CHIP_STM32F411VE is not set +CONFIG_ARCH_CHIP_STM32F405RG=y +# 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 is not set +# CONFIG_ARCH_CHIP_STM32F469B is not set +# CONFIG_ARCH_CHIP_STM32F469N is not set +CONFIG_STM32_FLASH_CONFIG_DEFAULT=y +# 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 is not set +# 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_STM32F33XX is not set +# CONFIG_STM32_STM32F37XX is not set +CONFIG_STM32_STM32F4XXX=y +# CONFIG_STM32_STM32F401 is not set +# CONFIG_STM32_STM32F410 is not set +# CONFIG_STM32_STM32F411 is not set +CONFIG_STM32_STM32F405=y +# 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 is not set +# 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_HRTIM1 is not set +# CONFIG_STM32_HAVE_LTDC is not set +CONFIG_STM32_HAVE_USART1=y +# CONFIG_STM32_HAVE_USART2 is not set +# CONFIG_STM32_HAVE_USART3 is not set +CONFIG_STM32_HAVE_UART4=y +# CONFIG_STM32_HAVE_UART5 is not set +CONFIG_STM32_HAVE_USART6=y +# CONFIG_STM32_HAVE_UART7 is not set +# CONFIG_STM32_HAVE_UART8 is not set +CONFIG_STM32_HAVE_TIM1=y +CONFIG_STM32_HAVE_TIM2=y +CONFIG_STM32_HAVE_TIM3=y +# CONFIG_STM32_HAVE_TIM4=y +CONFIG_STM32_HAVE_TIM5=y +#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_SDADC1 is not set +# CONFIG_STM32_HAVE_SDADC2 is not set +# CONFIG_STM32_HAVE_SDADC3 is not set +# CONFIG_STM32_HAVE_SDADC1_DMA is not set +# CONFIG_STM32_HAVE_SDADC2_DMA is not set +# CONFIG_STM32_HAVE_SDADC3_DMA is not set +CONFIG_STM32_HAVE_CAN1=y +CONFIG_STM32_HAVE_CAN2=y +# CONFIG_STM32_HAVE_COMP1 is not set +# CONFIG_STM32_HAVE_COMP2 is not set +# CONFIG_STM32_HAVE_COMP3 is not set +# CONFIG_STM32_HAVE_COMP4 is not set +# CONFIG_STM32_HAVE_COMP5 is not set +# CONFIG_STM32_HAVE_COMP6 is not set +# CONFIG_STM32_HAVE_COMP7 is not set +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_I2S3=y +# CONFIG_STM32_HAVE_SPI4 is not set +# CONFIG_STM32_HAVE_SPI5 is not set +# CONFIG_STM32_HAVE_SPI6 is not set +# CONFIG_STM32_HAVE_SAIPLL is not set +# CONFIG_STM32_HAVE_I2SPLL is not set +# CONFIG_STM32_HAVE_OPAMP1 is not set +# CONFIG_STM32_HAVE_OPAMP2 is not set +# CONFIG_STM32_HAVE_OPAMP3 is not set +# CONFIG_STM32_HAVE_OPAMP4 is not set +# TODO: 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 is not set +CONFIG_STM32_I2C2=y +# CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_OPAMP 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=y +# CONFIG_STM32_I2S3 is not set +CONFIG_STM32_SYSCFG=y +CONFIG_STM32_TIM1=y +# CONFIG_STM32_TIM2 is not set +CONFIG_STM32_TIM3=y +# CONFIG_STM32_TIM4 is not set +CONFIG_STM32_TIM5=y +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# 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 is not set +# CONFIG_STM32_USART3 is not set +CONFIG_STM32_UART4=y +# CONFIG_STM32_UART5 is not set +CONFIG_STM32_USART6=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_FLASH_WORKAROUND_DATA_CACHE_CORRUPTION_ON_RWW is not set +# 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_CCMEXCLUDE is not set +# CONFIG_STM32_CCM_PROCFS is not set +CONFIG_STM32_DMACAPABLE=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_TIM5_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_ADC_NO_STARTUP_CONV is not set +# 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_USART3_SERIALDRIVER=y +# CONFIG_STM32_USART3_1WIREDRIVER is not set +# CONFIG_USART3_RS485 is not set +# CONFIG_USART3_RXDMA is not set +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 + +# +# Serial Driver Configuration +# +CONFIG_STM32_SERIAL_RXDMA_BUFFER_SIZE=32 +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 +# CONFIG_STM32_I2C_DMA is not set +CONFIG_STM32_BBSRAM=y +CONFIG_STM32_BBSRAM_FILES=5 +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_MAGIC_TIME_SET=0xfacefeef +# 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 +# +# CONFIG_ARCH_TOOLCHAIN_IAR is not set +CONFIG_ARCH_TOOLCHAIN_GNU=y + +# +# 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_HAVE_RTC_SUBSECONDS is not set +# CONFIG_ARCH_USE_MPU is not set +CONFIG_ARCH_IRQPRIO=y +CONFIG_ARCH_STACKDUMP=n +# 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 +# CONFIG_ARCH_MINIMAL_VECTORTABLE 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=196608 +# CONFIG_ARCH_HAVE_SDRAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_OMNIBUS_F4SD=y +CONFIG_ARCH_BOARD="omnibus-f4sd" + +# +# Custom Board Configuration +# +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_RESET_ON_CRASH=y +# 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 +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +CONFIG_ARCH_IRQBUTTONS=y + +# +# Board-Specific Options +# +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_RESET_ON_CRASH=y +CONFIG_LIB_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +# CONFIG_BOARDCTL_UNIQUEID is not set +CONFIG_BOARDCTL_USBDEVCTRL=y +# CONFIG_BOARDCTL_TSCTEST 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_START_YEAR=2016 +CONFIG_START_MONTH=11 +CONFIG_START_DAY=30 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=50 +CONFIG_WDOG_INTRESERVE=4 +CONFIG_PREALLOC_TIMERS=50 + +# +# Tasks and Scheduling +# +# CONFIG_SPINLOCK is not set +# 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_PTHREAD_MUTEX_TYPES is not set +CONFIG_PTHREAD_MUTEX_ROBUST=y +# CONFIG_PTHREAD_MUTEX_UNSAFE is not set +# CONFIG_PTHREAD_MUTEX_BOTH is not set +CONFIG_NPTHREAD_KEYS=4 +# CONFIG_PTHREAD_CLEANUP is not set +# CONFIG_CANCELLATION_POINTS is not set + +# +# 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_SPINLOCKS 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=54 +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=249 +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=2600 +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_ARCH_HAVE_SPI_CRCGENERATION is not set +# CONFIG_ARCH_HAVE_SPI_CS_CONTROL is not set +CONFIG_ARCH_HAVE_SPI_BITORDER=y +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_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=y +CONFIG_MMCSD_SPICLOCK=24000000 +CONFIG_MMCSD_SPIMODE=0 +# CONFIG_ARCH_HAVE_SDIO is not set +# CONFIG_SDIO_DMA is not set +# CONFIG_ARCH_HAVE_SDIOWAIT_WRCOMPLETE is not set +# CONFIG_MODEM is not set +# CONFIG_MTD is not set + +# +# MTD Configuration +# +# CONFIG_MTD_PARTITION is not set +# CONFIG_MTD_SECT512 is not set +# CONFIG_MTD_PARTITION_NAMES is not set +# CONFIG_MTD_BYTE_WRITE is not set +# 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_MX25RXX is not set +# CONFIG_MTD_SMART is not set +# CONFIG_MTD_RAMTRON is not set +# CONFIG_RAMTRON_WRITEWAIT is not set +# CONFIG_RAMTRON_SETSPEED is not set +# CONFIG_RAMTRON_CHUNKING is not set +# 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=70 +CONFIG_DEV_FIFO_SIZE=0 +# CONFIG_PM is not set +# CONFIG_DRIVERS_SMPS is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS 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 is not set +# CONFIG_UART8_SERIALDRIVER is not set +# 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 is not set +# CONFIG_USART3_SERIALDRIVER is not set +# 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 is not set +# CONFIG_SERIAL_OFLOWCONTROL is not set +# CONFIG_SERIAL_DMA is not set +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=y +# CONFIG_USART6_SERIAL_CONSOLE is not set +# CONFIG_UART7_SERIAL_CONSOLE is not set +# CONFIG_OTHER_SERIAL_CONSOLE is not set +# CONFIG_NO_SERIAL_CONSOLE is not set + +# +# USART1 Configuration +# +CONFIG_USART1_RXBUFSIZE=300 +CONFIG_USART1_TXBUFSIZE=300 +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 + +# USART3 Configuration +# +#CONFIG_USART3_RXBUFSIZE=300 +#CONFIG_USART3_TXBUFSIZE=300 +#CONFIG_USART3_BAUD=115200 +#CONFIG_USART3_BITS=8 +#CONFIG_USART3_PARITY=0 +#CONFIG_USART3_2STOP=0 +# CONFIG_USART3_IFLOWCONTROL is not set +# CONFIG_USART3_OFLOWCONTROL is not set +# 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 +# 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_IFLOWCONTROL 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=2000 +CONFIG_CDCACM_VENDORID=0x26ac +CONFIG_CDCACM_PRODUCTID=0x0001 +CONFIG_CDCACM_VENDORSTR="3D Robotics" +CONFIG_CDCACM_PRODUCTSTR="OMNIBUSF4SD" +# CONFIG_USBMSC is not set +# CONFIG_RNDIS is not set +# CONFIG_USBHOST is not set +# CONFIG_USBMISC 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_SYSLOG_WRITE=y +# CONFIG_RAMLOG is not set +# CONFIG_SYSLOG_BUFFER 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_PSEUDOFS_SOFTLINKS 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 + +# +# Common I/O Buffer Support +# +# CONFIG_MM_IOB is not set + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Wireless Support +# +# CONFIG_WIRELESS is not set + +# +# 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 +# + +# +# Standard C I/O +# +# CONFIG_STDIO_DISABLE_BUFFERING is not set +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +# CONFIG_NOPRINTF_FIELDWIDTH is not set +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +# CONFIG_LIBC_SCANSET is not set +# 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 + +# +# Architecture-Specific Support +# +CONFIG_ARCH_LOWPUTC=y +# CONFIG_ARCH_ROMGETC is not set +CONFIG_LIBC_ARCH_MEMCPY=y +# CONFIG_LIBC_ARCH_MEMCMP is not set +# CONFIG_LIBC_ARCH_MEMMOVE is not set +# CONFIG_LIBC_ARCH_MEMSET is not set +# CONFIG_LIBC_ARCH_STRCHR is not set +# CONFIG_LIBC_ARCH_STRCMP is not set +# CONFIG_LIBC_ARCH_STRCPY is not set +# CONFIG_LIBC_ARCH_STRNCPY is not set +# CONFIG_LIBC_ARCH_STRLEN is not set +# CONFIG_LIBC_ARCH_STRNLEN is not set +# CONFIG_LIBC_ARCH_ELF is not set +CONFIG_ARMV7M_MEMCPY=y + +# +# stdlib Options +# +CONFIG_LIB_RAND_ORDER=1 +CONFIG_LIB_HOMEDIR="/" +CONFIG_LIBC_TMPDIR="/tmp" +CONFIG_LIBC_MAX_TMPFILE=32 + +# +# Program Execution Options +# +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 + +# +# errno Decode Support +# +CONFIG_LIBC_STRERROR=y +# CONFIG_LIBC_STRERROR_SHORT is not set +# CONFIG_LIBC_PERROR_STDOUT is not set + +# +# memcpy/memset Options +# +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MEMSET_64BIT=y +# CONFIG_LIBC_DLLFCN is not set +# CONFIG_LIBC_MODLIB is not set +# CONFIG_LIBC_WCHAR is not set +# CONFIG_LIBC_LOCALE is not set + +# +# Time/Time Zone Support +# +# CONFIG_LIBC_LOCALTIME is not set +CONFIG_TIME_EXTENDED=y +CONFIG_ARCH_HAVE_TLS=y + +# +# Thread Local Storage (TLS) +# +# CONFIG_TLS is not set + +# +# Network-Related Options +# +# CONFIG_LIBC_IPv4_ADDRCONV is not set +# CONFIG_LIBC_IPv6_ADDRCONV is not set +# CONFIG_LIBC_NETDB is not set + +# +# NETDB Support +# +# CONFIG_NETDB_HOSTFILE is not set +# CONFIG_LIBC_IOCTL_VARIADIC is not set +CONFIG_LIB_SENDFILE_BUFSIZE=512 + +# +# 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_CXX_NEWLONG is not set + +# +# LLVM C++ Library (libcxx) +# +# CONFIG_LIBCXX 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_APA102 is not set +# 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_FLOWC 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_MEDIA is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MTDPART 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_POWERMONITOR is not set +# CONFIG_EXAMPLES_PPPD is not set +# CONFIG_EXAMPLES_RFID_READUID is not set +# CONFIG_EXAMPLES_RGBLED 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_STAT is not set +# CONFIG_EXAMPLES_TCPECHO 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_WATCHDOG is not set +# CONFIG_EXAMPLES_WEBSERVER is not set +# CONFIG_EXAMPLES_XBC_TEST 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_BASENAME=y +# 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=y +# CONFIG_NSH_DISABLE_DF is not set +CONFIG_NSH_DISABLE_DIRNAME=y +# 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=y +CONFIG_NSH_DISABLE_IFCONFIG=y +CONFIG_NSH_DISABLE_IFUPDOWN=y +# CONFIG_NSH_DISABLE_KILL is not set +CONFIG_NSH_DISABLE_LOSETUP=y +CONFIG_NSH_DISABLE_LOSMART=y +# CONFIG_NSH_DISABLE_LS is not set +CONFIG_NSH_DISABLE_MB=y +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +CONFIG_NSH_DISABLE_MKFIFO=y +CONFIG_NSH_DISABLE_MKRD=y +CONFIG_NSH_DISABLE_MH=y +# 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=y +# CONFIG_NSH_DISABLE_PS is not set +CONFIG_NSH_DISABLE_PSSTACKUSAGE=y +CONFIG_NSH_DISABLE_PUT=y +# CONFIG_NSH_DISABLE_PWD is not set +CONFIG_NSH_DISABLE_REBOOT=y +# 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_SHUTDOWN=y +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_TEST is not set +CONFIG_NSH_DISABLE_TELNETD=y +# CONFIG_NSH_DISABLE_UMOUNT is not set +CONFIG_NSH_DISABLE_UNAME=y +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_NSH_DISABLE_WGET=y +CONFIG_NSH_DISABLE_XD=y +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 +CONFIG_NSH_MMCSDSPIPORTNO=2 + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +# CONFIG_NSH_CMDOPT_DD_STATS 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=0 +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 +CONFIG_HAVE_CXXINITIALIZE=y + +# +# System Libraries and NSH Add-Ons +# +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_CDCACM_DEVMINOR=0 +# CONFIG_SYSTEM_CLE is not set +# CONFIG_SYSTEM_CUTERM is not set +# 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 + +# +# Wireless Libraries and NSH Add-Ons +# + +# +# IEEE 802.15.4 applications +# +# CONFIG_IEEE802154_LIBMAC is not set +# CONFIG_IEEE802154_LIBUTILS is not set +# CONFIG_IEEE802154_I8SAK is not set diff --git a/platforms/nuttx/nuttx-configs/omnibus-f4sd/scripts/ld.script b/platforms/nuttx/nuttx-configs/omnibus-f4sd/scripts/ld.script new file mode 100644 index 0000000000..30076eba5c --- /dev/null +++ b/platforms/nuttx/nuttx-configs/omnibus-f4sd/scripts/ld.script @@ -0,0 +1,150 @@ +/**************************************************************************** + * configs/omnibus-f4sd/scripts/ld.script + * + * 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. + * + ****************************************************************************/ + +/* The STM32F405RG has 1024Kb of FLASH beginning at address 0x0800:0000 and + * 192Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of CCM 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 = 1008K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + 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) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.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) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/src/drivers/barometer/bmp280/bmp280.cpp b/src/drivers/barometer/bmp280/bmp280.cpp index bedb30cf54..d2b969a1de 100644 --- a/src/drivers/barometer/bmp280/bmp280.cpp +++ b/src/drivers/barometer/bmp280/bmp280.cpp @@ -584,8 +584,12 @@ struct bmp280_bus_option { #if defined(PX4_SPIDEV_EXT_BARO) && defined(PX4_SPI_BUS_EXT) { BMP280_BUS_SPI_EXTERNAL, "/dev/bmp280_spi_ext", &bmp280_spi_interface, PX4_SPI_BUS_EXT, PX4_SPIDEV_EXT_BARO, true, NULL }, #endif -#ifdef PX4_SPIDEV_BARO +#if defined(PX4_SPIDEV_BARO) +# if defined(PX4_SPIDEV_BARO_BUS) + { BMP280_BUS_SPI_INTERNAL, "/dev/bmp280_spi_int", &bmp280_spi_interface, PX4_SPIDEV_BARO_BUS, PX4_SPIDEV_BARO, false, NULL }, +# else { BMP280_BUS_SPI_INTERNAL, "/dev/bmp280_spi_int", &bmp280_spi_interface, PX4_SPI_BUS_SENSORS, PX4_SPIDEV_BARO, false, NULL }, +# endif #endif #ifdef PX4_I2C_OBDEV_BMP280 { BMP280_BUS_I2C_INTERNAL, "/dev/bmp280_i2c_int", &bmp280_i2c_interface, PX4_I2C_BUS_EXPANSION, PX4_I2C_OBDEV_BMP280, false, NULL }, diff --git a/src/drivers/boards/common/board_dma_alloc.c b/src/drivers/boards/common/board_dma_alloc.c index c7547be99e..c00068ec13 100644 --- a/src/drivers/boards/common/board_dma_alloc.c +++ b/src/drivers/boards/common/board_dma_alloc.c @@ -73,7 +73,7 @@ #if defined(BOARD_DMA_ALLOC_POOL_SIZE) # if !defined(CONFIG_GRAN) || !defined(CONFIG_FAT_DMAMEMORY) -# error microSD DMA support requires CONFIG_GRAN +# error microSD DMA support requires CONFIG_GRAN and CONFIG_FAT_DMAMEMORY # endif static GRAN_HANDLE dma_allocator; diff --git a/src/drivers/boards/omnibus-f4sd/CMakeLists.txt b/src/drivers/boards/omnibus-f4sd/CMakeLists.txt new file mode 100644 index 0000000000..3d8de289cc --- /dev/null +++ b/src/drivers/boards/omnibus-f4sd/CMakeLists.txt @@ -0,0 +1,49 @@ +############################################################################ +# +# Copyright (c) 2018 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(drivers_board + init.c + led.c + spi.c + timer_config.c + usb.c +) + +target_link_libraries(drivers_board + PRIVATE + drivers__led # drv_led_start + nuttx_apps # up_cxxinitialize + nuttx_arch # sdio + nuttx_drivers # sdio + parameters # param_init +) diff --git a/src/drivers/boards/omnibus-f4sd/board_config.h b/src/drivers/boards/omnibus-f4sd/board_config.h new file mode 100644 index 0000000000..d2ef3ee0ee --- /dev/null +++ b/src/drivers/boards/omnibus-f4sd/board_config.h @@ -0,0 +1,340 @@ +/**************************************************************************** + * + * Copyright (c) 2018, 2014 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 + * + * omnibusf4sd internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ +/* Configuration ************************************************************************************/ + +/* omnibusf4sd GPIOs ***********************************************************************************/ +/* LEDs */ +// power - green +// LED1 - PB5 - blue +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5) +#define GPIO_LED_BLUE GPIO_LED1 + +/* GPS + * UART6 + */ +#define GPS_DEFAULT_UART_PORT "/dev/ttyS2" + +/* + * 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 + */ +// TODO: ADCs, eg. pixracer +//#define ADC_CHANNELS (1 << 2) | (1 << 3) | (1 << 4) | (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) + +// Placeholder +#define ADC_BATTERY_VOLTAGE_CHANNEL ((uint8_t)(-1)) +#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1)) +#define ADC_AIRSPEED_VOLTAGE_CHANNEL ((uint8_t)(-1)) + +// TODO: ADCs +//#define ADC_BATTERY_VOLTAGE_CHANNEL 2 +//#define ADC_BATTERY_CURRENT_CHANNEL 3 +//#define ADC_5V_RAIL_SENSE 4 +//#define ADC_RC_RSSI_CHANNEL 11 + +/* Define Battery 1 Voltage Divider and A per V + */ + +// TODO: +//#define BOARD_BATTERY1_V_DIV (13.653333333f) +//#define BOARD_BATTERY1_A_PER_V (36.367515152f) + +/* User GPIOs + * + * GPIO0-5 are the PWM servo outputs. + * GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_1 //PB0 S1_OUT D1_ST7 + * GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_1 //PB1 S2_OUT D1_ST2 + * GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1 //PA3 S3_OUT D1_ST6 + * GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1 //PA2 S4_OUT D1_ST1 + * GPIO_TIM5_CH2OUT GPIO_TIM5_CH2OUT_1 //PA1 S5_OUT + * GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_1 //PA8 S6_OUT + */ + +#define _MK_GPIO_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLUP)) + +#define GPIO_GPIO0_INPUT _MK_GPIO_INPUT(GPIO_TIM3_CH3IN) +#define GPIO_GPIO1_INPUT _MK_GPIO_INPUT(GPIO_TIM3_CH4IN) +#define GPIO_GPIO2_INPUT _MK_GPIO_INPUT(GPIO_TIM2_CH4IN) +#define GPIO_GPIO3_INPUT _MK_GPIO_INPUT(GPIO_TIM2_CH3IN) +//#define GPIO_GPIO4_INPUT _MK_GPIO_INPUT(GPIO_TIM5_CH2IN) +//#define GPIO_GPIO5_INPUT _MK_GPIO_INPUT(GPIO_TIM1_CH1IN) + +#define _MK_GPIO_OUTPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR)) + +#define GPIO_GPIO0_OUTPUT _MK_GPIO_OUTPUT(GPIO_TIM3_CH3OUT) +#define GPIO_GPIO1_OUTPUT _MK_GPIO_OUTPUT(GPIO_TIM3_CH4OUT) +#define GPIO_GPIO2_OUTPUT _MK_GPIO_OUTPUT(GPIO_TIM2_CH4OUT) +#define GPIO_GPIO3_OUTPUT _MK_GPIO_OUTPUT(GPIO_TIM2_CH3OUT) +//#define GPIO_GPIO4_OUTPUT _MK_GPIO_OUTPUT(GPIO_TIM5_CH2OUT) +//#define GPIO_GPIO5_OUTPUT _MK_GPIO_OUTPUT(GPIO_TIM1_CH1OUT) + +/*----------------------------------------------------------*/ +/* OMNIBUSF4SD SPI chip selects and DRDY */ +/*----------------------------------------------------------*/ + +/* SPI chip selects */ +/* + * Define the Chip Selects for SPI1 + * + * MPU6000: PA4 + * + */ +#define GPIO_SPI_CS_MEMS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + +/* + * Define the Chip Selects for SPI2 + * + * SD Card: PB12 + * + */ +#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN12) + +/* + * Define the Chip Selects for SPI3 + * + * BMP280: PB3 + * ABT7456: PA15 + * + */ + +#define GPIO_SPI3_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN3) +#define GPIO_SPI3_CS_OSD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN15) + +/* + * 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)) + +/* SPI 1 bus 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) +/* SPI 1 CS's off */ +#define GPIO_SPI1_CS_MEMS_OFF _PIN_OFF(GPIO_SPI_CS_MEMS) + +/* SPI 2 bus off */ +#define GPIO_SPI2_SCK_OFF _PIN_OFF(GPIO_SPI2_SCK) +#define GPIO_SPI2_MISO_OFF _PIN_OFF(GPIO_SPI2_MISO) +#define GPIO_SPI2_MOSI_OFF _PIN_OFF(GPIO_SPI2_MOSI) +/* SPI 2 CS's off */ +#define GPIO_SPI2_CS_SDCARD_OFF _PIN_OFF(GPIO_SPI_CS_SDCARD) + +/* SPI 3 bus off */ +#define GPIO_SPI3_SCK_OFF _PIN_OFF(GPIO_SPI3_SCK) +#define GPIO_SPI3_MISO_OFF _PIN_OFF(GPIO_SPI3_MISO) +#define GPIO_SPI3_MOSI_OFF _PIN_OFF(GPIO_SPI3_MOSI) +/* SPI 3 CS's off */ +#define GPIO_SPI3_CS_BARO_OFF _PIN_OFF(GPIO_SPI3_CS_BARO) + +// One device per bus +#define PX4_SPI_BUS_SENSORS 1 +#define PX4_SPIDEV_MPU 1 +#define PX4_SPIDEV_BARO_BUS 3 +#define PX4_SPIDEV_BARO 1 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTC|GPIO_PIN5) + +/*----------------------------------------------------------*/ +/* End OMNIBUSF4SD SPI chip selects and DRDY */ +/*----------------------------------------------------------*/ + +#define PX4_SPI_BUS_BARO 3 + +#define PX4_I2C_BUS_EXPANSION 2 +#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION + +/* PWM + * + * 6 PWM outputs are configured. + * + * Alternatively CH3/CH4 could be assigned to UART6_TX/RX + * + * Pins: + * + * INPUTS: + * CH1 : PB8 : TIM10_CH1 // PPM + * CH2 : PB9 : TIM4_CH4 + * CH3 : PC6 : TIM8_CH1 // OR UART6_TX + * CH4 : PC7 : TIM8_CH2 // OR UART6_RX + * CH5 : PC8 : TIM8_CH3 + * CH6 : PC9 : TIM8_CH4 + * + * OUTPUTS: + * M1 : PB0 : TIM3_CH3 + * M2 : PB1 : TIM3_CH4 + * M3 : PA3 : TIM2_CH3 + * M4 : PA2 : TIM2_CH4 + * M5 : PA1 : TIM5_CH2 // UART4_RX + * M6 : PA8 : TIM1_CH1 // USART2_TX + */ + +#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_1 //PB0 S1_OUT D1_ST7 +#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_1 //PB1 S2_OUT D1_ST2 +#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1 //PA3 S3_OUT D1_ST6 +#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1 //PA2 S4_OUT D1_ST1 + +#define DIRECT_PWM_OUTPUT_CHANNELS 4 + +#define GPIO_TIM3_CH3IN GPIO_TIM3_CH3IN_1 +#define GPIO_TIM3_CH4IN GPIO_TIM3_CH4IN_1 +#define GPIO_TIM2_CH4IN GPIO_TIM2_CH4IN_1 +#define GPIO_TIM2_CH3IN GPIO_TIM2_CH3IN_1 + +#define DIRECT_INPUT_TIMER_CHANNELS 4 + +// Has pwm outputs +#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS + +/* High-resolution timer */ +#define HRT_TIMER 4 // T4C1 +#define HRT_TIMER_CHANNEL 1 // use capture/compare channel 1 + +#define HRT_PPM_CHANNEL 3 // capture/compare channel 3 +#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF2|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN8) + +#define RC_SERIAL_PORT "/dev/ttyS0" + +/* + * One RC_IN + * + * GPIO PPM_IN on PB8 T4CH3 + * SPEKTRUM_RX (it's TX or RX in Bind) on PA10 UART1 + * The FMU can drive GPIO PPM_IN as an output + */ +// TODO? +//#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN6) +//#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +//#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(GPIO_USART1_RX) +//#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +#define BOARD_NAME "OMNIBUS_F4SD" + +#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}, } + +/* + * PX4FMUv4 GPIO numbers. + * + * There are no alternate functions on this board. + */ +#define GPIO_SERVO_1 (1<<0) /**< servo 1 output */ +#define GPIO_SERVO_2 (1<<1) /**< servo 2 output */ +#define GPIO_SERVO_3 (1<<2) /**< servo 3 output */ +#define GPIO_SERVO_4 (1<<3) /**< servo 4 output */ + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +#define BOARD_HAS_ON_RESET 1 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + * mask - is bus selection + * 1 - 1 << 0 + * 2 - 1 << 1 + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); +void board_spi_reset(int ms); + + +/**************************************************************************************************** + * Name: stm32_usbinitialize + * + * Description: + * Called to configure USB IO. + * + ****************************************************************************************************/ + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include "../common/board_common.h" + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/src/drivers/boards/omnibus-f4sd/init.c b/src/drivers/boards/omnibus-f4sd/init.c new file mode 100644 index 0000000000..0b5df40f25 --- /dev/null +++ b/src/drivers/boards/omnibus-f4sd/init.c @@ -0,0 +1,507 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2018 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * omnibusf4sd-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include + +#include "platform/cxxinitialize.h" +#include +#include +#include +#include +#include +#include + +#include +#include "board_config.h" +#include + +#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) +{ + UNUSED(ms); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + /* configure the GPIO pins to outputs and keep them low */ + + 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); + + /* On resets invoked from system (not boot) insure we establish a low + * output state (discharge the pins) on PWM pins before they become inputs. + */ + + if (status >= 0) { + up_mdelay(400); + } +} + +/************************************************************************************ + * 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) +{ + /* Reset all PWM to Low outputs */ + + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + + //TODO: ADCs + ///* configure ADC pins */ + //stm32_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */ + //stm32_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */ + //stm32_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */ + //stm32_configgpio(GPIO_ADC1_IN11); /* RSSI analog in */ + + // TODO: power peripherals + ///* configure power supply control/sense pins */ + //stm32_configgpio(GPIO_PERIPH_3V3_EN); + //stm32_configgpio(GPIO_VDD_BRICK_VALID); + //stm32_configgpio(GPIO_VDD_USB_VALID); + + // TODO: 3v3 Sensor? + ///* Start with Sensor voltage off We will enable it + // * in board_app_initialize + // */ + //stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN); + + // TODO: SBUS inversion? SPEK power? + //stm32_configgpio(GPIO_SBUS_INV); + //stm32_configgpio(GPIO_SPEKTRUM_PWR_EN); + + // TODO: $$$ Unused? + //stm32_configgpio(GPIO_8266_GPIO0); + //stm32_configgpio(GPIO_8266_PD); + //stm32_configgpio(GPIO_8266_RST); + + /* Safety - led don in led driver */ + + // TODO: unused? + //stm32_configgpio(GPIO_BTN_SAFETY); + + // TODO: RSSI + //stm32_configgpio(GPIO_RSSI_IN); + + stm32_configgpio(GPIO_PPM_IN); + + /* configure SPI all interfaces GPIO */ + + stm32_spiinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +static struct spi_dev_s *spi1; +static struct spi_dev_s *spi2; +static struct spi_dev_s *spi3; + +__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(); + + param_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_BLUE); + + /* Configure SPI-based devices */ + + // SPI1: MPU6000 + spi1 = stm32_spibus_initialize(1); + + if (!spi1) { + message("[boot] FAILED to initialize SPI port 1\n"); + 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_MPU, false); + up_udelay(20); + + // SPI2: SDCard + /* Get the SPI port for the microSD slot */ + spi2 = stm32_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO); + + if (!spi2) { + message("[boot] FAILED to initialize SPI port %d\n", CONFIG_NSH_MMCSDSPIPORTNO); + return -ENODEV; + } + + /* Now bind the SPI interface to the MMCSD driver */ + int result = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, CONFIG_NSH_MMCSDSLOTNO, spi2); + + if (result != OK) { + message("[boot] FAILED to bind SPI port 2 to the MMCSD driver\n"); + return -ENODEV; + } + + up_udelay(20); + + + // SPI3: OSD / Baro + spi3 = stm32_spibus_initialize(3); + + if (!spi3) { + message("[boot] FAILED to initialize SPI port 3\n"); + board_autoled_on(LED_RED); + return -ENODEV; + } + + /* Copied from fmu-v4 + * Default SPI3 to 12MHz and de-assert the known chip selects. + * MS5611 has max SPI clock speed of 20MHz + */ + + // BMP280 max SPI speed is 10 MHz + SPI_SETFREQUENCY(spi3, 10 * 1000 * 1000); + SPI_SETBITS(spi3, 8); + SPI_SETMODE(spi3, SPIDEV_MODE3); + SPI_SELECT(spi3, PX4_SPIDEV_BARO, false); + up_udelay(20); + + return OK; +} diff --git a/src/drivers/boards/omnibus-f4sd/led.c b/src/drivers/boards/omnibus-f4sd/led.c new file mode 100644 index 0000000000..06b3f7a752 --- /dev/null +++ b/src/drivers/boards/omnibus-f4sd/led.c @@ -0,0 +1,125 @@ +/**************************************************************************** + * + * Copyright (c) 2018 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * omnibusf4sd 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, +}; + +__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); +} + +__EXPORT void led_on(int led) +{ + phy_set_led(led, true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(led, false); +} + +__EXPORT void board_autoled_initialize(void) +{ + /* Configure LED1 GPIO for output */ + stm32_configgpio(GPIO_LED1); +} + +__EXPORT void board_autoled_on(int led) + +{ + if (led == 1) { + /* Pull down to switch on */ + stm32_gpiowrite(GPIO_LED1, false); + } +} + +__EXPORT void board_autoled_off(int led) + +{ + if (led == 1) { + /* Pull up to switch off */ + stm32_gpiowrite(GPIO_LED1, true); + } +} + +__EXPORT void led_toggle(int led) +{ + if (led == 1) { + if (stm32_gpioread(GPIO_LED1)) { + stm32_gpiowrite(GPIO_LED1, false); + + } else { + stm32_gpiowrite(GPIO_LED1, true); + } + } +} diff --git a/src/drivers/boards/omnibus-f4sd/spi.c b/src/drivers/boards/omnibus-f4sd/spi.c new file mode 100644 index 0000000000..f40a8961ca --- /dev/null +++ b/src/drivers/boards/omnibus-f4sd/spi.c @@ -0,0 +1,184 @@ +/**************************************************************************** + * + * Copyright (C) 2018 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file 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. + * mask - is bus selection + * 1 - 1 << 0 + * 2 - 1 << 1 + * + ************************************************************************************/ + +__EXPORT void stm32_spiinitialize() +{ + stm32_configgpio(GPIO_SPI_CS_MEMS); + stm32_configgpio(GPIO_SPI_CS_SDCARD); + stm32_configgpio(GPIO_SPI3_CS_BARO); +} + +__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + /* SPI select is active low, so write !selected to select the device */ + UNUSED(devid); + px4_arch_gpiowrite(GPIO_SPI_CS_MEMS, !selected); +} + +__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return SPI_STATUS_PRESENT; +} + +__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + /* SPI select is active low, so write !selected to select the device */ + UNUSED(devid); + px4_arch_gpiowrite(GPIO_SPI_CS_SDCARD, !selected); +} + +__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return SPI_STATUS_PRESENT; +} + +__EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + UNUSED(devid); + /* SPI select is active low, so write !selected to select the device */ + px4_arch_gpiowrite(GPIO_SPI3_CS_BARO, !selected); +} + +__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + /* FRAM is always present */ + return SPI_STATUS_PRESENT; +} + +__EXPORT void board_spi_reset(int ms) +{ + // TODO: DRDY + ///* disable SPI bus 1 DRDY */ + //stm32_configgpio(GPIO_DRDY_OFF_PORTD_PIN15); + //stm32_configgpio(GPIO_DRDY_OFF_PORTC_PIN14); + //stm32_configgpio(GPIO_DRDY_OFF_PORTE_PIN12); + + //stm32_gpiowrite(GPIO_DRDY_OFF_PORTD_PIN15, 0); + //stm32_gpiowrite(GPIO_DRDY_OFF_PORTC_PIN14, 0); + //stm32_gpiowrite(GPIO_DRDY_OFF_PORTE_PIN12, 0); + + /* disable SPI bus 1 CS */ + stm32_configgpio(GPIO_SPI1_CS_MEMS_OFF); + stm32_gpiowrite(GPIO_SPI1_CS_MEMS_OFF, 0); + + /* disable SPI bus 2 CS */ + stm32_configgpio(GPIO_SPI2_CS_SDCARD_OFF); + stm32_gpiowrite(GPIO_SPI2_CS_SDCARD_OFF, 0); + + /* disable SPI bus 3 CS */ + stm32_configgpio(GPIO_SPI3_CS_BARO_OFF); + stm32_gpiowrite(GPIO_SPI3_CS_BARO_OFF, 0); + + /* disable SPI bus 1*/ + 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); + + /* disable SPI bus 2*/ + stm32_configgpio(GPIO_SPI2_SCK_OFF); + stm32_configgpio(GPIO_SPI2_MISO_OFF); + stm32_configgpio(GPIO_SPI2_MOSI_OFF); + + stm32_gpiowrite(GPIO_SPI2_SCK_OFF, 0); + stm32_gpiowrite(GPIO_SPI2_MISO_OFF, 0); + stm32_gpiowrite(GPIO_SPI2_MOSI_OFF, 0); + + /* disable SPI bus 3*/ + stm32_configgpio(GPIO_SPI3_SCK_OFF); + stm32_configgpio(GPIO_SPI3_MISO_OFF); + stm32_configgpio(GPIO_SPI3_MOSI_OFF); + + stm32_gpiowrite(GPIO_SPI3_SCK_OFF, 0); + stm32_gpiowrite(GPIO_SPI3_MISO_OFF, 0); + stm32_gpiowrite(GPIO_SPI3_MOSI_OFF, 0); + + /* wait a bit before starting SPI, different times didn't influence results */ + usleep(100); + + stm32_spiinitialize(); + + stm32_configgpio(GPIO_SPI1_SCK); + stm32_configgpio(GPIO_SPI1_MISO); + stm32_configgpio(GPIO_SPI1_MOSI); + + // TODO: why do we not enable SPI2 here? + + stm32_configgpio(GPIO_SPI3_SCK); + stm32_configgpio(GPIO_SPI3_MISO); + stm32_configgpio(GPIO_SPI3_MOSI); +} diff --git a/src/drivers/boards/omnibus-f4sd/timer_config.c b/src/drivers/boards/omnibus-f4sd/timer_config.c new file mode 100644 index 0000000000..23783b9b7a --- /dev/null +++ b/src/drivers/boards/omnibus-f4sd/timer_config.c @@ -0,0 +1,120 @@ +/**************************************************************************** + * + * Copyright (C) 2018 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* + * @file 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_TIM2_BASE, + .clock_register = STM32_RCC_APB1ENR, + .clock_bit = RCC_APB1ENR_TIM2EN, + .clock_freq = STM32_APB1_TIM2_CLKIN, + .first_channel_index = 0, + .last_channel_index = 1, + .handler = io_timer_handler1, + .vectorno = STM32_IRQ_TIM2 + }, + { + .base = STM32_TIM3_BASE, + .clock_register = STM32_RCC_APB1ENR, + .clock_bit = RCC_APB1ENR_TIM3EN, + .clock_freq = STM32_APB1_TIM3_CLKIN, + .first_channel_index = 2, + .last_channel_index = 3, + .handler = io_timer_handler2, + .vectorno = STM32_IRQ_TIM3 + } +}; +/* + * OUTPUTS: + * M3 : PA3 : TIM2_CH3 + * M4 : PA2 : TIM2_CH4 + * M1 : PB0 : TIM3_CH3 + * M2 : PB1 : TIM3_CH4 + */ + +__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + //PB0 S1_OUT D1_ST7 + { + .gpio_out = GPIO_TIM3_CH3OUT, + .gpio_in = GPIO_TIM3_CH3IN, + .timer_index = 1, + .timer_channel = 3, + .ccr_offset = STM32_GTIM_CCR3_OFFSET, + .masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF + }, + //PB1 S2_OUT D1_ST2 + { + .gpio_out = GPIO_TIM3_CH4OUT, + .gpio_in = GPIO_TIM3_CH4IN, + .timer_index = 1, + .timer_channel = 4, + .ccr_offset = STM32_GTIM_CCR4_OFFSET, + .masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF + }, + //PA3 S3_OUT D1_ST6 + { + .gpio_out = GPIO_TIM2_CH4OUT, + .gpio_in = GPIO_TIM2_CH4IN, + .timer_index = 0, + .timer_channel = 4, + .ccr_offset = STM32_GTIM_CCR4_OFFSET, + .masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF + }, + //PA2 S4_OUT D1_ST1 + { + .gpio_out = GPIO_TIM2_CH3OUT, + .gpio_in = GPIO_TIM2_CH3IN, + .timer_index = 0, + .timer_channel = 3, + .ccr_offset = STM32_GTIM_CCR3_OFFSET, + .masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF + } +}; diff --git a/src/drivers/boards/omnibus-f4sd/usb.c b/src/drivers/boards/omnibus-f4sd/usb.c new file mode 100644 index 0000000000..e66d0d5f00 --- /dev/null +++ b/src/drivers/boards/omnibus-f4sd/usb.c @@ -0,0 +1,108 @@ +/**************************************************************************** + * + * Copyright (C) 2018 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file 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 omnibusf4sd 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); +} + diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 38ce64a227..06028b3382 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -1144,7 +1144,9 @@ void PX4FMU::set_rc_scan_state(RC_SCAN newState) void PX4FMU::rc_io_invert(bool invert) { +#ifdef INVERT_RC_INPUT INVERT_RC_INPUT(invert); +#endif } #endif