From ad8539bd153e3e1f2c10fe05a1af60ad28bdd7d6 Mon Sep 17 00:00:00 2001 From: Mark Sauder Date: Mon, 15 Oct 2018 09:53:29 -0600 Subject: [PATCH] Deprecate the tap_common directory, nuttx, driver, and makefile references to tap-v1. (#10629) --- .ci/Jenkinsfile-compile | 2 +- Makefile | 1 - ROMFS/tap_common/CMakeLists.txt | 35 - ROMFS/tap_common/init.d/4001_quad_x | 22 - ROMFS/tap_common/init.d/6001_hexa_x | 26 - ROMFS/tap_common/init.d/CMakeLists.txt | 46 - ROMFS/tap_common/init.d/rc.fw_apps | 20 - ROMFS/tap_common/init.d/rc.fw_defaults | 23 - ROMFS/tap_common/init.d/rc.interface | 83 - ROMFS/tap_common/init.d/rc.mc_apps | 17 - ROMFS/tap_common/init.d/rc.mc_defaults | 33 - ROMFS/tap_common/init.d/rc.sensors | 28 - ROMFS/tap_common/init.d/rc.vtol_apps | 24 - ROMFS/tap_common/init.d/rc.vtol_defaults | 43 - ROMFS/tap_common/init.d/rcS | 367 ---- ROMFS/tap_common/mixers/CMakeLists.txt | 39 - ROMFS/tap_common/mixers/README.md | 105 -- ROMFS/tap_common/mixers/gear.mix | 7 - ROMFS/tap_common/mixers/hexa_x.main.mix | 3 - ROMFS/tap_common/mixers/quad_x.main.mix | 7 - cmake/configs/nuttx_tap-v1_default.cmake | 78 - platforms/nuttx/Images/tap-v1.prototype | 13 - .../nuttx-configs/tap-v1/include/board.h | 444 ----- .../tap-v1/include/nsh_romfsimg.h | 42 - .../nuttx/nuttx-configs/tap-v1/nsh/defconfig | 1604 ----------------- .../nuttx-configs/tap-v1/scripts/ld.script | 151 -- src/drivers/boards/tap-v1/CMakeLists.txt | 52 - src/drivers/boards/tap-v1/board_config.h | 351 ---- src/drivers/boards/tap-v1/init.c | 400 ---- src/drivers/boards/tap-v1/led.c | 107 -- src/drivers/boards/tap-v1/pwr.c | 185 -- src/drivers/boards/tap-v1/sdio.c | 122 -- src/drivers/boards/tap-v1/spi.c | 85 - src/drivers/boards/tap-v1/timer_config.c | 109 -- src/drivers/boards/tap-v1/usb.c | 127 -- 35 files changed, 1 insertion(+), 4800 deletions(-) delete mode 100644 ROMFS/tap_common/CMakeLists.txt delete mode 100644 ROMFS/tap_common/init.d/4001_quad_x delete mode 100644 ROMFS/tap_common/init.d/6001_hexa_x delete mode 100644 ROMFS/tap_common/init.d/CMakeLists.txt delete mode 100644 ROMFS/tap_common/init.d/rc.fw_apps delete mode 100644 ROMFS/tap_common/init.d/rc.fw_defaults delete mode 100644 ROMFS/tap_common/init.d/rc.interface delete mode 100644 ROMFS/tap_common/init.d/rc.mc_apps delete mode 100644 ROMFS/tap_common/init.d/rc.mc_defaults delete mode 100644 ROMFS/tap_common/init.d/rc.sensors delete mode 100644 ROMFS/tap_common/init.d/rc.vtol_apps delete mode 100644 ROMFS/tap_common/init.d/rc.vtol_defaults delete mode 100644 ROMFS/tap_common/init.d/rcS delete mode 100644 ROMFS/tap_common/mixers/CMakeLists.txt delete mode 100644 ROMFS/tap_common/mixers/README.md delete mode 100644 ROMFS/tap_common/mixers/gear.mix delete mode 100644 ROMFS/tap_common/mixers/hexa_x.main.mix delete mode 100644 ROMFS/tap_common/mixers/quad_x.main.mix delete mode 100644 cmake/configs/nuttx_tap-v1_default.cmake delete mode 100644 platforms/nuttx/Images/tap-v1.prototype delete mode 100644 platforms/nuttx/nuttx-configs/tap-v1/include/board.h delete mode 100644 platforms/nuttx/nuttx-configs/tap-v1/include/nsh_romfsimg.h delete mode 100644 platforms/nuttx/nuttx-configs/tap-v1/nsh/defconfig delete mode 100644 platforms/nuttx/nuttx-configs/tap-v1/scripts/ld.script delete mode 100644 src/drivers/boards/tap-v1/CMakeLists.txt delete mode 100644 src/drivers/boards/tap-v1/board_config.h delete mode 100644 src/drivers/boards/tap-v1/init.c delete mode 100644 src/drivers/boards/tap-v1/led.c delete mode 100644 src/drivers/boards/tap-v1/pwr.c delete mode 100644 src/drivers/boards/tap-v1/sdio.c delete mode 100644 src/drivers/boards/tap-v1/spi.c delete mode 100644 src/drivers/boards/tap-v1/timer_config.c delete mode 100644 src/drivers/boards/tap-v1/usb.c diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index 55c260f20a..f6dc68e418 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -89,7 +89,7 @@ pipeline { def nuttx_builds_archive = [ target: ["px4fmu-v2_default", "px4fmu-v3_default", "px4fmu-v4_default", "px4fmu-v4pro_default", "px4fmu-v5_default", "px4fmu-v5_rtps", "px4fmu-v5_stackcheck", "aerofc-v1_default", "aerocore2_default", "auav-x21_default", "av-x-v1_default", "crazyflie_default", "mindpx-v2_default", - "nxphlite-v3_default", "tap-v1_default", "omnibus-f4sd_default"], + "nxphlite-v3_default", "omnibus-f4sd_default"], image: docker_images.nuttx, archive: true ] diff --git a/Makefile b/Makefile index fa9a779169..a25bc49b12 100644 --- a/Makefile +++ b/Makefile @@ -219,7 +219,6 @@ misc_qgc_extra_firmware: \ check_crazyflie_default \ check_mindpx-v2_default \ check_px4fmu-v2_lpe \ - check_tap-v1_default \ sizes # Other NuttX firmware diff --git a/ROMFS/tap_common/CMakeLists.txt b/ROMFS/tap_common/CMakeLists.txt deleted file mode 100644 index be3e27cb99..0000000000 --- a/ROMFS/tap_common/CMakeLists.txt +++ /dev/null @@ -1,35 +0,0 @@ -############################################################################ -# -# 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. -# -############################################################################ - -add_subdirectory(init.d) -add_subdirectory(mixers) diff --git a/ROMFS/tap_common/init.d/4001_quad_x b/ROMFS/tap_common/init.d/4001_quad_x deleted file mode 100644 index ff867b3cad..0000000000 --- a/ROMFS/tap_common/init.d/4001_quad_x +++ /dev/null @@ -1,22 +0,0 @@ -#!nsh -# -# @name Generic Quadrotor X config -# -# @type Quadrotor x -# @class Copter -# -# @output AUX1 feed-through of RC AUX1 channel -# @output AUX2 feed-through of RC AUX2 channel -# @output AUX3 feed-through of RC AUX3 channel -# -# @maintainer Lorenz Meier -# - -sh /etc/init.d/rc.mc_defaults -if tap_esc start -d /dev/ttyS4 -n 4 -then -fi -set OUTPUT_MODE tap_esc -param set BAT_N_CELLS 4 - -set MIXER quad_x diff --git a/ROMFS/tap_common/init.d/6001_hexa_x b/ROMFS/tap_common/init.d/6001_hexa_x deleted file mode 100644 index 826926a04e..0000000000 --- a/ROMFS/tap_common/init.d/6001_hexa_x +++ /dev/null @@ -1,26 +0,0 @@ -#!nsh -# -# @name Generic Hexarotor x geometry -# -# @type Hexarotor x -# @class Copter -# -# @output AUX1 feed-through of RC AUX1 channel -# @output AUX2 feed-through of RC AUX2 channel -# @output AUX3 feed-through of RC AUX3 channel -# -# @maintainer Lorenz Meier -# - -sh /etc/init.d/rc.mc_defaults - -param set MAV_TYPE 13 -param set MC_YAWRATE_P 0.12 -param set CAL_MAG0_ROT 6 - -if tap_esc start -d /dev/ttyS4 -n 6 -then -fi -set OUTPUT_MODE tap_esc - -set MIXER hexa_x diff --git a/ROMFS/tap_common/init.d/CMakeLists.txt b/ROMFS/tap_common/init.d/CMakeLists.txt deleted file mode 100644 index 44323342f2..0000000000 --- a/ROMFS/tap_common/init.d/CMakeLists.txt +++ /dev/null @@ -1,46 +0,0 @@ -############################################################################ -# -# 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_romfs_files( - 4001_quad_x - 6001_hexa_x - rc.fw_apps - rc.fw_defaults - rc.interface - rc.mc_apps - rc.mc_defaults - rcS - rc.sensors - rc.vtol_apps - rc.vtol_defaults - ) diff --git a/ROMFS/tap_common/init.d/rc.fw_apps b/ROMFS/tap_common/init.d/rc.fw_apps deleted file mode 100644 index 040bcbde03..0000000000 --- a/ROMFS/tap_common/init.d/rc.fw_apps +++ /dev/null @@ -1,20 +0,0 @@ -#!nsh -# -# Standard apps for fixed wing -# - -# -# Start the attitude and position estimator -# -ekf2 start - -# -# Start attitude controller -# -fw_att_control start -fw_pos_control_l1 start - -# -# Start Land Detector -# -land_detector start fixedwing diff --git a/ROMFS/tap_common/init.d/rc.fw_defaults b/ROMFS/tap_common/init.d/rc.fw_defaults deleted file mode 100644 index 74777e6167..0000000000 --- a/ROMFS/tap_common/init.d/rc.fw_defaults +++ /dev/null @@ -1,23 +0,0 @@ -#!nsh - -set VEHICLE_TYPE fw - -if [ $AUTOCNF = yes ] -then -# -# Default parameters for FW -# - param set RTL_RETURN_ALT 100 - param set RTL_DESCEND_ALT 100 - param set RTL_LAND_DELAY -1 - - param set NAV_ACC_RAD 50 -fi - -# This is the gimbal pass mixer -set MIXER_AUX pass -set PWM_AUX_RATE 50 -set PWM_AUX_OUT 1234 -set PWM_AUX_DISARMED 1500 -set PWM_AUX_MIN 1000 -set PWM_AUX_MAX 2000 diff --git a/ROMFS/tap_common/init.d/rc.interface b/ROMFS/tap_common/init.d/rc.interface deleted file mode 100644 index 11979210bb..0000000000 --- a/ROMFS/tap_common/init.d/rc.interface +++ /dev/null @@ -1,83 +0,0 @@ -#!nsh -# -# Script to configure control interface -# - -set SDCARD_MIXERS_PATH /fs/microsd/etc/mixers - -if [ $MIXER != none -a $MIXER != skip ] -then - # - # Load main mixer - # - - # Use the mixer file - set MIXER_FILE /etc/mixers/$MIXER.main.mix - - set OUTPUT_DEV /dev/pwm_output0 - - if [ $OUTPUT_MODE = tap_esc ] - then - set OUTPUT_DEV /dev/tap_esc - fi - - if mixer load $OUTPUT_DEV $MIXER_FILE - then - echo "INFO [init] Mixer: $MIXER_FILE on $OUTPUT_DEV" - else - echo "ERROR [init] Error loading mixer: $MIXER_FILE" - echo "ERROR:[init] Could not load mixer: $MIXER_FILE" >> $LOG_FILE - tune_control play -t 20 - fi - - unset MIXER_FILE -else - if [ $MIXER != skip ] - then - echo "ERROR [init] Mixer not defined" - echo "ERROR [init] Mixer not defined" >> $LOG_FILE - tune_control play -t 20 - fi -fi - -if [ $OUTPUT_MODE = fmu -o $OUTPUT_MODE = io ] -then - if [ $PWM_OUT != none ] - then - # - # Set PWM output frequency - # - if [ $PWM_RATE != none ] - then - pwm rate -c $PWM_OUT -r $PWM_RATE - fi - - # - # Set disarmed, min and max PWM values - # - if [ $PWM_DISARMED != none ] - then - pwm disarmed -c $PWM_OUT -p $PWM_DISARMED - fi - if [ $PWM_MIN != none ] - then - pwm min -c $PWM_OUT -p $PWM_MIN - fi - if [ $PWM_MAX != none ] - then - pwm max -c $PWM_OUT -p $PWM_MAX - fi - fi - - if [ $FAILSAFE != none ] - then - pwm failsafe -d $OUTPUT_DEV $FAILSAFE - fi -fi - -unset PWM_OUT -unset PWM_RATE -unset PWM_MIN -unset PWM_MAX -unset FAILSAFE -unset OUTPUT_DEV diff --git a/ROMFS/tap_common/init.d/rc.mc_apps b/ROMFS/tap_common/init.d/rc.mc_apps deleted file mode 100644 index 607dffd5b0..0000000000 --- a/ROMFS/tap_common/init.d/rc.mc_apps +++ /dev/null @@ -1,17 +0,0 @@ -#!nsh -# -# Standard apps for multirotors: -# att & pos estimator, att & pos control. -# - - -ekf2 start - -mc_att_control start - -mc_pos_control start - -# -# Start Land Detector -# -land_detector start multicopter diff --git a/ROMFS/tap_common/init.d/rc.mc_defaults b/ROMFS/tap_common/init.d/rc.mc_defaults deleted file mode 100644 index f7ca870b7f..0000000000 --- a/ROMFS/tap_common/init.d/rc.mc_defaults +++ /dev/null @@ -1,33 +0,0 @@ -#!nsh - -set VEHICLE_TYPE mc - -if [ $AUTOCNF = yes ] -then - param set PWM_DISARMED 900 - param set PWM_MIN 1075 - param set PWM_MAX 1950 -fi - -param set NAV_ACC_RAD 2.0 -param set MIS_TAKEOFF_ALT 2.5 -param set RTL_RETURN_ALT 30.0 -param set RTL_DESCEND_ALT 10.0 -param set RTL_LAND_DELAY 0 -param set MPC_THR_MIN 0.10 -param set MPC_MANTHR_MIN 0.04 - -# set environment variables (!= parameters) -set PWM_RATE 400 -# tell the mixer to use parameters for these instead -set PWM_DISARMED p:PWM_DISARMED -set PWM_MIN p:PWM_MIN -set PWM_MAX p:PWM_MAX - -# This is the gimbal pass mixer -set MIXER_AUX pass -set PWM_AUX_RATE 50 -set PWM_AUX_OUT 1234 -set PWM_AUX_DISARMED 1500 -set PWM_AUX_MIN 1000 -set PWM_AUX_MAX 2000 diff --git a/ROMFS/tap_common/init.d/rc.sensors b/ROMFS/tap_common/init.d/rc.sensors deleted file mode 100644 index 391199627a..0000000000 --- a/ROMFS/tap_common/init.d/rc.sensors +++ /dev/null @@ -1,28 +0,0 @@ -#!nsh -# -# Standard startup script for TAP v1 onboard sensor drivers. -# - -if adc start -then -fi - -if ms5611 -T 5607 -I start -then -fi - -# External I2C bus -if hmc5883 -C -T -X start -then -fi - -# Internal I2C bus -if mpu6000 -I -T 6000 start -then -fi - -# Wait 50 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire) -usleep 50000 -if sensors start -then -fi diff --git a/ROMFS/tap_common/init.d/rc.vtol_apps b/ROMFS/tap_common/init.d/rc.vtol_apps deleted file mode 100644 index 0ae3f28950..0000000000 --- a/ROMFS/tap_common/init.d/rc.vtol_apps +++ /dev/null @@ -1,24 +0,0 @@ -#!nsh -# -# Standard apps for vtol: -# att & pos estimator, att & pos control. -# -# - - -#--------------------------------------- -# Estimator group selction -# -ekf2 start - -vtol_att_control start -mc_att_control start -mc_pos_control start -fw_att_control start -fw_pos_control_l1 start - -# -# Start Land Detector -# Multicopter for now until we have something for VTOL -# -land_detector start vtol diff --git a/ROMFS/tap_common/init.d/rc.vtol_defaults b/ROMFS/tap_common/init.d/rc.vtol_defaults deleted file mode 100644 index 1dbff43e25..0000000000 --- a/ROMFS/tap_common/init.d/rc.vtol_defaults +++ /dev/null @@ -1,43 +0,0 @@ -#!nsh - -set VEHICLE_TYPE vtol - -if [ $AUTOCNF = yes ] -then - param set MC_ROLL_P 6.0 - param set MC_PITCH_P 6.0 - param set MC_YAW_P 4 - - # - # Default parameters for mission and position handling - # - param set NAV_ACC_RAD 3 - param set MPC_TKO_SPEED 1.0 - param set MPC_LAND_SPEED 0.7 - param set MPC_Z_VEL_MAX_DN 1.5 - param set MPC_XY_VEL_MAX 4.0 - param set MIS_YAW_TMT 10 - param set MPC_ACC_HOR_MAX 2.0 - param set RTL_LAND_DELAY 0 -fi - -# set environment variables (!= parameters) -set PWM_RATE 400 -# tell the mixer to use parameters for these instead -set PWM_DISARMED p:PWM_DISARMED -set PWM_MIN p:PWM_MIN -set PWM_MAX p:PWM_MAX - -# Transitional support: ensure suitable PWM min/max param values -if param compare PWM_MIN 1000 -then - param set PWM_MIN 1075 -fi -if param compare PWM_MAX 2000 -then - param set PWM_MAX 1950 -fi -if param compare PWM_DISARMED 0 -then - param set PWM_DISARMED 900 -fi diff --git a/ROMFS/tap_common/init.d/rcS b/ROMFS/tap_common/init.d/rcS deleted file mode 100644 index d90962e929..0000000000 --- a/ROMFS/tap_common/init.d/rcS +++ /dev/null @@ -1,367 +0,0 @@ -#!nsh -# -# TAP startup script. -# -# NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS. -# - -# Serial map: -# /dev/ttyS0: GPS -# /dev/ttyS1: GB -# /dev/ttyS2: nsh shell / console -# /dev/ttyS3: payload -# /dev/ttyS4: esc bus -# /dev/ttyS5: RC input - -# -# Start CDC/ACM serial driver -# -sercon - -set LOG_FILE /fs/microsd/bootlog.txt -set DATAMAN_OPT -r - -# -# Start the ORB (first app to start) -# tone_alarm and tune_control -# is dependent. -# -uorb start - -# -# Start the tone_alarm driver. -# -tone_alarm start - -# -# Try to mount the microSD card. -# -if mount -t vfat /dev/mmcsd0 /fs/microsd -then - echo "microSD present" - unset DATAMAN_OPT -else - if mkfatfs /dev/mmcsd0 - then - if mount -t vfat /dev/mmcsd0 /fs/microsd - then - echo "microSD card formatted" - unset DATAMAN_OPT - else - echo "ERROR [init] Format failed" - tune_control play -t 17 - set LOG_FILE /dev/null - fi - else - set LOG_FILE /dev/null - fi -fi - -# -# Load parameters -# -set PARAM_FILE /fs/microsd/params -if mtd start -then - set PARAM_FILE /fs/mtd_params -fi - -param select $PARAM_FILE -if !param load -then - param reset -fi - -# -# Start system state indicator -# -if rgbled_pwm start -then -fi - -if rgbled start -then -fi - -# -# Set parameters and env variables for selected AUTOSTART -# -if param compare SYS_AUTOSTART 0 -then - param set SYS_AUTOSTART 6001 - param set SYS_AUTOCONFIG 1 -fi - -# -# Set AUTOCNF flag to use it in AUTOSTART scripts -# -if param compare SYS_AUTOCONFIG 1 -then - # Wipe out params except RC* - param reset_nostart RC* - set AUTOCNF yes -else - set AUTOCNF no -fi - -# -# Set default values -# -set VEHICLE_TYPE none -set MIXER none -set OUTPUT_MODE none -set PWM_OUT none -set PWM_RATE none -set PWM_DISARMED none -set PWM_MIN none -set PWM_MAX none -set FMU_MODE pwm -set MAV_TYPE none -set FAILSAFE none - -# Start canned airframe config -sh /etc/init.d/rc.autostart - -# -# If autoconfig parameter was set, reset it and save parameters -# -if [ $AUTOCNF = yes ] -then - param set SYS_AUTOCONFIG 0 - param save -fi -unset AUTOCNF - -# -# Set default output if not set -# -if [ $OUTPUT_MODE = none ] -then - if [ $USE_IO = yes ] - then - set OUTPUT_MODE io - else - set OUTPUT_MODE fmu - fi -fi - -gps start -d /dev/ttyS0 - -# waypoint storage -# REBOOTWORK this needs to start in parallel -if dataman start $DATAMAN_OPT -then -fi - -# -# Sensors System (start before Commander so Preflight checks are properly run) -# -sh /etc/init.d/rc.sensors - -commander start - -# -# Start CPU load monitor -# -load_mon start - -# Start MAVLink on the gimbal port -#mavlink start -r 1200 -d /dev/ttyS1 - -# Start MAVLink on USB, developers can use the MAVLink shell -mavlink start -r 60000 -d /dev/ttyACM0 -m config - -# -# Logging -# -#if logger start -b 2 -t -#then -#fi - -# -# Fixed wing setup -# -if [ $VEHICLE_TYPE = fw ] -then - echo "INFO [init] Fixedwing" - - if [ $MIXER = none ] - then - # Set default mixer for fixed wing if not defined - set MIXER AERT - fi - - if [ $MAV_TYPE = none ] - then - # Use MAV_TYPE = 1 (fixed wing) if not defined - set MAV_TYPE 1 - fi - - param set MAV_TYPE $MAV_TYPE - - # Load mixer and configure outputs - sh /etc/init.d/rc.interface - - # Start standard fixedwing apps - sh /etc/init.d/rc.fw_apps -fi - -# -# Multicopters setup -# -if [ $VEHICLE_TYPE = mc ] -then - echo "INFO [init] Multicopter" - - if [ $MIXER = none ] - then - echo "INFO [init] Mixer undefined" - fi - - if [ $MAV_TYPE = none ] - then - # Use mixer to detect vehicle type - if [ $MIXER = quad_x -o $MIXER = quad_+ ] - then - set MAV_TYPE 2 - fi - if [ $MIXER = quad_w ] - then - set MAV_TYPE 2 - fi - if [ $MIXER = quad_h ] - then - set MAV_TYPE 2 - fi - if [ $MIXER = tri_y_yaw- -o $MIXER = tri_y_yaw+ ] - then - set MAV_TYPE 15 - fi - if [ $MIXER = hexa_x -o $MIXER = hexa_+ ] - then - set MAV_TYPE 13 - fi - if [ $MIXER = hexa_cox ] - then - set MAV_TYPE 13 - fi - if [ $MIXER = octo_x -o $MIXER = octo_+ ] - then - set MAV_TYPE 14 - fi - fi - - # Still no MAV_TYPE found - if [ $MAV_TYPE = none ] - then - echo "WARN [init] Unknown MAV_TYPE" - param set MAV_TYPE 2 - else - param set MAV_TYPE $MAV_TYPE - fi - - # Load mixer and configure outputs - sh /etc/init.d/rc.interface - - # Start standard multicopter apps - sh /etc/init.d/rc.mc_apps -fi - -# -# VTOL setup -# -if [ $VEHICLE_TYPE = vtol ] -then - echo "INFO [init] VTOL" - - if [ $MIXER = none ] - then - echo "WARN [init] VTOL mixer undefined" - fi - - if [ $MAV_TYPE = none ] - then - # Use mixer to detect vehicle type - if [ $MIXER = caipirinha_vtol ] - then - set MAV_TYPE 19 - fi - if [ $MIXER = firefly6 ] - then - set MAV_TYPE 21 - fi - if [ $MIXER = quad_x_pusher_vtol ] - then - set MAV_TYPE 22 - fi - fi - - # Still no MAV_TYPE found - if [ $MAV_TYPE = none ] - then - echo "WARN [init] Unknown MAV_TYPE" - param set MAV_TYPE 19 - else - param set MAV_TYPE $MAV_TYPE - fi - - # Load mixer and configure outputs - sh /etc/init.d/rc.interface - - # Start standard vtol apps - sh /etc/init.d/rc.vtol_apps -fi - -# -# UGV/Rover setup -# -if [ $VEHICLE_TYPE = ugv ] -then - # 10 is MAV_TYPE_GROUND_ROVER - set MAV_TYPE 10 - - # Load mixer and configure outputs - sh /etc/init.d/rc.interface - - # Start standard rover apps - sh /etc/init.d/rc.ugv_apps - - param set MAV_TYPE 10 -fi - -unset MIXER -unset MAV_TYPE -unset OUTPUT_MODE - -# -# Start the RC input driver -# -if fmu mode_pwm1 -then -fi - -# -# Use 400 Hz PWM output for landing gear (frequency also affects RGB LED) -# -pwm rate -c 1 -r 400 - -# -# Load the gear mixer onto fmu -# -mixer load /dev/px4fmu /etc/mixers/gear.mix - -# -# Start the navigator -# -if navigator start -then -fi - -# There is no further script processing, so we can free some RAM -# XXX potentially unset all script variables. -unset TUNE_ERR -unset LOG_FILE -unset DATAMAN_OPT - -# Boot is complete, inform MAVLink app(s) that the system is now fully up and running -mavlink boot_complete diff --git a/ROMFS/tap_common/mixers/CMakeLists.txt b/ROMFS/tap_common/mixers/CMakeLists.txt deleted file mode 100644 index c341a9610c..0000000000 --- a/ROMFS/tap_common/mixers/CMakeLists.txt +++ /dev/null @@ -1,39 +0,0 @@ -############################################################################ -# -# 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_romfs_files( - gear.mix - hexa_x.main.mix - hexa_x.main.mix - quad_x.main.mix -) diff --git a/ROMFS/tap_common/mixers/README.md b/ROMFS/tap_common/mixers/README.md deleted file mode 100644 index 0e591ca288..0000000000 --- a/ROMFS/tap_common/mixers/README.md +++ /dev/null @@ -1,105 +0,0 @@ -## PX4 mixer definitions ## - -Files in this directory implement example mixers that can be used as a basis -for customisation, or for general testing purposes. - -For a detailed description of the mixing architecture and examples see: -http://px4.io/dev/mixing - -### Syntax ### - -Mixer definitions are text files; lines beginning with a single capital letter -followed by a colon are significant. All other lines are ignored, meaning that -explanatory text can be freely mixed with the definitions. - -Each file may define more than one mixer; the allocation of mixers to actuators -is specific to the device reading the mixer definition, and the number of -actuator outputs generated by a mixer is specific to the mixer. - -For example: each simple or null mixer is assigned to outputs 1 to x -in the order they appear in the mixer file. - -A mixer begins with a line of the form - - : - -The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a -multirotor mixer, etc. - -#### Null Mixer #### - -A null mixer consumes no controls and generates a single actuator output whose -value is always zero. Typically a null mixer is used as a placeholder in a -collection of mixers in order to achieve a specific pattern of actuator outputs. - -The null mixer definition has the form: - - Z: - -#### Simple Mixer #### - -A simple mixer combines zero or more control inputs into a single actuator -output. Inputs are scaled, and the mixing function sums the result before -applying an output scaler. - -A simple mixer definition begins with: - - M: - O: <-ve scale> <+ve scale> - -If is zero, the sum is effectively zero and the mixer will -output a fixed value that is constrained by and . - -The second line defines the output scaler with scaler parameters as discussed -above. Whilst the calculations are performed as floating-point operations, the -values stored in the definition file are scaled by a factor of 10000; i.e. an -offset of -0.5 is encoded as -5000. - -The definition continues with entries describing the control -inputs and their scaling, in the form: - - S: <-ve scale> <+ve scale> - -The value identifies the control group from which the scaler will read, -and the value an offset within that group. These values are specific to -the device reading the mixer definition. - -When used to mix vehicle controls, mixer group zero is the vehicle attitude -control group, and index values zero through three are normally roll, pitch, -yaw and thrust respectively. - -The remaining fields on the line configure the control scaler with parameters as -discussed above. Whilst the calculations are performed as floating-point -operations, the values stored in the definition file are scaled by a factor of -10000; i.e. an offset of -0.5 is encoded as -5000. - -#### Multirotor Mixer #### - -The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust) -into a set of actuator outputs intended to drive motor speed controllers. - -The mixer definition is a single line of the form: - - R: - -The supported geometries include: - - * 4x - quadrotor in X configuration - * 4+ - quadrotor in + configuration - * 6x - hexcopter in X configuration - * 6+ - hexcopter in + configuration - * 8x - octocopter in X configuration - * 8+ - octocopter in + configuration - -Each of the roll, pitch and yaw scale values determine scaling of the roll, -pitch and yaw controls relative to the thrust control. Whilst the calculations -are performed as floating-point operations, the values stored in the definition -file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000. - -Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the -thrust input ranges from 0.0 to 1.0. Output for each actuator is in the -range -1.0 to 1.0. - -In the case where an actuator saturates, all actuator values are rescaled so that -the saturating actuator is limited to 1.0. diff --git a/ROMFS/tap_common/mixers/gear.mix b/ROMFS/tap_common/mixers/gear.mix deleted file mode 100644 index 20f202d3e6..0000000000 --- a/ROMFS/tap_common/mixers/gear.mix +++ /dev/null @@ -1,7 +0,0 @@ -# -# This maps actuator_controls_0[7] to the first and only PWM output -# - -M: 1 -O: 10000 10000 0 -10000 10000 -S: 0 7 10000 10000 0 -10000 10000 diff --git a/ROMFS/tap_common/mixers/hexa_x.main.mix b/ROMFS/tap_common/mixers/hexa_x.main.mix deleted file mode 100644 index 16e6e22f90..0000000000 --- a/ROMFS/tap_common/mixers/hexa_x.main.mix +++ /dev/null @@ -1,3 +0,0 @@ -# Hexa X - -R: 6x 10000 10000 10000 0 diff --git a/ROMFS/tap_common/mixers/quad_x.main.mix b/ROMFS/tap_common/mixers/quad_x.main.mix deleted file mode 100644 index bf034e7c1f..0000000000 --- a/ROMFS/tap_common/mixers/quad_x.main.mix +++ /dev/null @@ -1,7 +0,0 @@ -R: 4x 10000 10000 10000 0 -M: 1 -O: 10000 10000 0 -10000 10000 -S: 3 5 10000 10000 0 -10000 10000 -M: 1 -O: 10000 10000 0 -10000 10000 -S: 3 6 10000 10000 0 -10000 10000 diff --git a/cmake/configs/nuttx_tap-v1_default.cmake b/cmake/configs/nuttx_tap-v1_default.cmake deleted file mode 100644 index 144ee28126..0000000000 --- a/cmake/configs/nuttx_tap-v1_default.cmake +++ /dev/null @@ -1,78 +0,0 @@ - -px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT tap_common) - -set(target_definitions MEMORY_CONSTRAINED_SYSTEM) - -set(config_module_list - # - # Board support modules - # - drivers/barometer - drivers/differential_pressure - drivers/gps - drivers/magnetometer/hmc5883 - drivers/imu/mpu6000 - drivers/px4fmu - drivers/rgbled_pwm - drivers/rc_input - drivers/stm32 - drivers/stm32/adc - drivers/stm32/tone_alarm - drivers/tap_esc - drivers/vmount - modules/sensors - - # - # System commands - # - systemcmds/bl_update - systemcmds/led_control - systemcmds/mixer - systemcmds/param - systemcmds/perf - systemcmds/pwm - systemcmds/hardfault_log - systemcmds/motor_test - systemcmds/reboot - systemcmds/top - systemcmds/config - systemcmds/nshterm - systemcmds/mtd - systemcmds/dumpfile - systemcmds/ver - systemcmds/topic_listener - systemcmds/tune_control - - # - # General system control - # - modules/commander - modules/load_mon - modules/navigator - modules/mavlink - modules/land_detector - - # - # Estimation modules (EKF/ SO3 / other filters) - # - modules/ekf2 - - # - # Vehicle Control - # - modules/fw_pos_control_l1 - modules/fw_att_control - modules/mc_att_control - modules/mc_pos_control - modules/vtol_att_control - - # - # Logging - # - modules/logger - - # - # Library modules - # - modules/dataman -) diff --git a/platforms/nuttx/Images/tap-v1.prototype b/platforms/nuttx/Images/tap-v1.prototype deleted file mode 100644 index 3e31b74370..0000000000 --- a/platforms/nuttx/Images/tap-v1.prototype +++ /dev/null @@ -1,13 +0,0 @@ -{ - "board_id": 64, - "magic": "PX4FWv1", - "description": "Firmware for the TAPv1 board", - "image": "", - "build_time": 0, - "summary": "TAPv1", - "version": "0.1", - "image_size": 0, - "image_maxsize": 999424, - "git_identity": "", - "board_revision": 0 -} diff --git a/platforms/nuttx/nuttx-configs/tap-v1/include/board.h b/platforms/nuttx/nuttx-configs/tap-v1/include/board.h deleted file mode 100644 index cfd837267e..0000000000 --- a/platforms/nuttx/nuttx-configs/tap-v1/include/board.h +++ /dev/null @@ -1,444 +0,0 @@ -/************************************************************************************ - * configs/tap-v1/include/board.h - * include/arch/board/board.h - * - * Copyright (C) 2012-2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * David Sidrane - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************************/ - -#ifndef __CONFIG_TAP_V1_INCLUDE_BOARD_H -#define __CONFIG_TAP_V1_INCLUDE_BOARD_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#ifndef __ASSEMBLY__ -# include -#endif - -#include "stm32_rcc.h" -#include "stm32_sdio.h" -#include "stm32.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* Clocking *************************************************************************/ -/* The TAP V1 uses a 16MHz crystal connected to the HSE. - * - * 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) : 16000000 (STM32_BOARD_XTAL) - * PLLM : 8 (STM32_PLLCFG_PLLM) - * PLLN : 168 (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 16MHz - * LSE - not installed - */ - -#define STM32_BOARD_XTAL 16000000ul - -#define STM32_HSI_FREQUENCY 16000000ul -#define STM32_LSI_FREQUENCY 32000 -#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL - -/* Main PLL Configuration. - * - * PLL source is HSE - * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN - * = (16,000,000 / 8) * 168 - * = 336,000,000 - * SYSCLK = PLL_VCO / PLLP - * = 336,000,000 / 2 = 168,000,000 - * USB OTG FS, SDIO and RNG Clock - * = PLL_VCO / PLLQ - * = 336,000,000 / 7 - * = 48,000,000 - */ - -#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8) -#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(168) -#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 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 - -/* 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() - * - * PC4 BLUE_LED D4 Blue LED cathode - * PC5 RED_LED D5 Red LED cathode -*/ -#define BOARD_LED1 0 -#define BOARD_LED2 1 -#define BOARD_NLEDS 2 - -#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 tap-v1. The following definitions describe how NuttX controls - * the LEDs: - */ - -#define LED_STARTED 0 /* BLUE */ -#define LED_HEAPALLOCATE 1 /* LED2 */ -#define LED_IRQSENABLED 2 /* BLUE */ -#define LED_STACKCREATED 3 /* BLUE + RED */ -#define LED_INIRQ 4 /* BLUE */ -#define LED_SIGNAL 5 /* RED */ -#define LED_ASSERTION 6 /* BLUE + RED */ -#define LED_PANIC 7 /* BLUE + RED */ - -/* Alternate function pin selections ************************************************/ - -/* - * USARTs. - * - * - * Peripheral Port Signal Name CONN - * USART1_TX PB6 GPS_USART1_TX JP1-15,16 - * USART1_RX PB7 GPS_USART1_RX JP1-13,14 - * USART2_TX PA2 GB_USART2_TX JP2-19,20 - * USART2_RX PA3 GB_USART2_RX JP2-21,22 - * USART3_TX PC10 RF2_USART3_TX J3-2 - * USART3_RX PC11 RF2_USART3_RX J3-1 - * USART6_TX PC6 RF_USART6_TX JP2-15,16 - * USART6_RX PC7 RF_USART6_RX JP2-17,18 -*/ - -#define GPIO_USART1_TX GPIO_USART1_TX_2 -#define GPIO_USART1_RX GPIO_USART1_RX_2 - -#define GPIO_USART2_TX GPIO_USART2_TX_1 -#define GPIO_USART2_RX GPIO_USART2_RX_1 - -#define GPIO_USART3_TX GPIO_USART3_TX_2 -#define GPIO_USART3_RX GPIO_USART3_RX_2 - -#define GPIO_USART6_TX GPIO_USART6_TX_1 -#define GPIO_USART6_RX GPIO_USART6_RX_1 - -/* USART DMA configuration for USART 1 and 6 */ - -#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2 -#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 - -/* - * UARTs. - * - * N.B. The 's' is here to match the wrong labeling on Schematic - * - * Peripheral Port Signal Name CONN - * UART4_TX PA0 OFS_UsART4_TX JP1-19,20 - * UART4_RX PA1 OFS_UsART4_RX JP1-17,18 - * UART5_TX PC12 ESC_UsART5_TX U7-HCT244 etal ESC - * UART5_RX PD2 ESC_UsART5_RX U8-5 74HCT151 - * - * Note that UART5 has no optional pinout, so it is not listed here. - * -*/ - -#define GPIO_UART4_TX GPIO_UART4_TX_1 -#define GPIO_UART4_RX GPIO_UART4_RX_1 - -/* - * I2C - * - * Peripheral Port Signal Name CONN - * I2C1_SDA PB9 I2C1_SDA J2-4,9,16,21 mpu6050, U4 MS6507 - * I2C1_SDL PB8 I2C1_SCL J2-3,10,15,22 mpu6050, U4 MS6507 - * I2C2_SDA PB11 Sonar Echo/I2C_SDA JP2-31,32 - * I2C2_SDL PB10 Sonar Trig/I2C_SCL JP2-29,30 - * I2C3_SDA PC9 COMPASS_I2C3_SDA JP1-27,28 - * I2C3_SDL PA8 COMPASS_I2C3_SCL JP1-25,26 - * - * The optional _GPIO configurations allow the I2C driver to manually - * reset the bus to clear stuck slaves. They match the pin configuration, - * but are normally-high GPIOs. - */ -#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 -#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 -#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) -#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8) - -#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 -#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 -#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11) -#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10) - -#define GPIO_I2C3_SDA GPIO_I2C3_SDA_1 -#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 -#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN9) -#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8) - -/* - * SPI - * - * Peripheral Port Signal Name CONN - * SPI2_NSS PB12 SD_SPI2_NSS SD-2 CS - * SPI2_SCK PB13 SD_SPI2_SCK SD-5 CLK - * SPI2_MISO PB14 SD_SPI2_MISO SD-7 D0 - * SPI2_MOSI PB15 SD_SPI2_MOSI SD-3 DI - * - */ - -#define GPIO_SPI2_NSS (GPIO_SPI2_NSS_1 | GPIO_SPEED_50MHz) -#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_2 | GPIO_SPEED_50MHz) -#define GPIO_SPI2_MISO (GPIO_SPI2_MISO_1 | GPIO_SPEED_50MHz) -#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1 | GPIO_SPEED_50MHz) - -/* SPI DMA configuration for SPI2 (microSD) */ -#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX -#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX - -/* The following Pin Mapping is just for completeness */ -/* - * JTAG - * - * We will only enable SW-DP, JTAG-DP will be disabled - * - * Function Port Signal Name CONN - * SWDIO PA13 DAT J10-3,J7 - * SWCLK PA14 CLK J10-4,J8 - * - */ - -/* - * BOOT - * - * Function Port Signal Name CONN - * BOOT0 NA BOOT0 GND via 10 K - * BOOT1 PB2 BOOT1 V3.3 - 10 K - * - * As jumpered the device can only boot from FLASH. - * - * It can be booted to: - * - * SRAM if BOOT0 is pulled High with 1K. - * System memory if: - * BOOT0 is pulled High with 1K and - * BOOT1 is pulled Low with 1K -*/ - -/* - * Timer PWM - * - * Peripheral Port Signal Name CONN - * TIM3_CH1 PA6 LED_R JP2-23,24 - * TIM3_CH2 PA7 LED_G JP2-25,26 - * TIM3_CH3 PB0 LED_B JP2-27,28 - * TIM3_CH4 PB1 nPWM_1 AUX1(Landing Gear) JP1-21,22 - */ - -/* - * GPIO - * - * Port Signal Name CONN - * PA4 POWER JP1-23, - Must be held High to run w/o USB - * PB4 TEMP_CONT J2-2,11,14,23 - Gyro Heater - * PC0 VOLTAGE JP2-13,14 - 1.84 @16.66 1.67 @15.12 Scale 0.1105 - * PC1 KEY_AD JP1-31,32 - Low when Power button is depressed - * PC2 SD_SW SD-9 SW - Card Present - * PC3 PCON_RADIO JP1-29,30 - * PC13 S2 U8-9 74HCT151 - * PC14 S1 U8-10 74HCT151 - * PC15 S0 U8-11 74HCT151 - */ - -/* - * USB - * - * Port Signal Name CONN - * PA9 OTG_FS_VBUS J1-1 - * PA10 OTG_FS_ID J1-4 - * PA11 OTG_FS_DM J1-2 - * PA12 OTG_FS_DP J1-3 - */ - -/* - * UNUSED PINS - In an idle world - these would have been tied to pads to - * facilitate debugging probs. - * Port - * PA15 - * PB3 - * PB5 - * PC8 -*/ - -/* Board provides GPIO or other Hardware for signaling to timing analyzer */ - -#if defined(CONFIG_BOARD_USE_PROBES) -# define PROBE_N(n) (1<<((n)-1)) -# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) -# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN3) -# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5) -# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8) - -# define PROBE_INIT(mask) \ - do { \ - if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ - if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ - if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ - if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ - } while(0) - -# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) -# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) -#else -# define PROBE_INIT(mask) -# define PROBE(n,s) -# define PROBE_MARK(n) -#endif - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ -/************************************************************************************ - * Name: stm32_boardinitialize - * - * Description: - * All STM32 architectures must provide the following entry point. This entry point - * is called early in the initialization -- after all memory has been configured - * and mapped but before any devices have been initialized. - * - ************************************************************************************/ - -EXTERN void stm32_boardinitialize(void); - -#undef EXTERN -#if defined(__cplusplus) -} -#endif - -#endif /* __ASSEMBLY__ */ -#endif /* __CONFIG_TAP_V1_INCLUDE_BOARD_H */ diff --git a/platforms/nuttx/nuttx-configs/tap-v1/include/nsh_romfsimg.h b/platforms/nuttx/nuttx-configs/tap-v1/include/nsh_romfsimg.h deleted file mode 100644 index beb1a924cf..0000000000 --- a/platforms/nuttx/nuttx-configs/tap-v1/include/nsh_romfsimg.h +++ /dev/null @@ -1,42 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * nsh_romfsetc.h - * - * This file is a stub for 'make export' purposes; the actual ROMFS - * must be supplied by the library client. - */ - -extern unsigned char romfs_img[]; -extern unsigned int romfs_img_len; diff --git a/platforms/nuttx/nuttx-configs/tap-v1/nsh/defconfig b/platforms/nuttx/nuttx-configs/tap-v1/nsh/defconfig deleted file mode 100644 index 09bf23a38e..0000000000 --- a/platforms/nuttx/nuttx-configs/tap-v1/nsh/defconfig +++ /dev/null @@ -1,1604 +0,0 @@ -# -# 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_ARM926EJS is not set -# CONFIG_ARCH_ARM920T 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_USART3=y -CONFIG_STM32_HAVE_UART4=y -CONFIG_STM32_HAVE_UART5=y -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 is not set -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 is not set -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 -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_FSMC is not set -# CONFIG_STM32_HASH is not set -CONFIG_STM32_I2C1=y -CONFIG_STM32_I2C2=y -CONFIG_STM32_I2C3=y -# 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 is not set -# CONFIG_STM32_SPI1 is not set -CONFIG_STM32_SPI2=y -# CONFIG_STM32_SPI3 is not set -# CONFIG_STM32_I2S3 is not set -CONFIG_STM32_SYSCFG=y -# CONFIG_STM32_TIM1 is not set -# CONFIG_STM32_TIM2 is not set -# CONFIG_STM32_TIM3 is not set -CONFIG_STM32_TIM4=y -CONFIG_STM32_TIM5=y -CONFIG_STM32_TIM6=y -CONFIG_STM32_TIM7=y -# CONFIG_STM32_TIM8 is not set -CONFIG_STM32_TIM9=y -CONFIG_STM32_TIM10=y -CONFIG_STM32_TIM11=y -CONFIG_STM32_TIM12=y -CONFIG_STM32_TIM13=y -CONFIG_STM32_TIM14=y -CONFIG_STM32_USART1=y -CONFIG_STM32_USART2=y -CONFIG_STM32_USART3=y -CONFIG_STM32_UART4=y -CONFIG_STM32_UART5=y -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_TIM4_PWM is not set -# CONFIG_STM32_TIM5_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_TIM12_PWM is not set -# CONFIG_STM32_TIM13_PWM is not set -# CONFIG_STM32_TIM14_PWM is not set -# CONFIG_STM32_TIM4_ADC is not set -# CONFIG_STM32_TIM5_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_USART2_SERIALDRIVER=y -# CONFIG_STM32_USART2_1WIREDRIVER is not set -# CONFIG_USART2_RS485 is not set -CONFIG_USART2_RXDMA=y -CONFIG_STM32_USART3_SERIALDRIVER=y -# CONFIG_STM32_USART3_1WIREDRIVER is not set -# CONFIG_USART3_RS485 is not set -CONFIG_USART3_RXDMA=y -CONFIG_STM32_UART4_SERIALDRIVER=y -# CONFIG_STM32_UART4_1WIREDRIVER is not set -# CONFIG_UART4_RS485 is not set -CONFIG_UART4_RXDMA=y -CONFIG_STM32_UART5_SERIALDRIVER=y -# CONFIG_STM32_UART5_1WIREDRIVER is not set -# CONFIG_UART5_RS485 is not set -CONFIG_UART5_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 is not set - -# -# 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 is not set -CONFIG_ARCH_STACKDUMP=y -# CONFIG_ENDIAN_BIG is not set -# CONFIG_ARCH_IDLE_CUSTOM is not set -# CONFIG_ARCH_HAVE_RAMFUNCS is not set -CONFIG_ARCH_HAVE_RAMVECTORS=y -# CONFIG_ARCH_RAMVECTORS is not set -# 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 is not set - -# -# 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_TAP_V1=y -CONFIG_ARCH_BOARD="tap-v1" - -# -# Custom Board Configuration -# -# CONFIG_BOARD_CUSTOM_LEDS is not set -# CONFIG_BOARD_CUSTOM_BUTTONS is not set -CONFIG_BOARD_HAS_PROBES=y -# CONFIG_BOARD_USE_PROBES is not set - -# -# Common Board Options -# - -# -# Board-Specific Options -# -CONFIG_BOARD_CRASHDUMP=y -CONFIG_BOARD_RESET_ON_CRASH=y -CONFIG_LIB_BOARDCTL=y -CONFIG_BOARDCTL_RESET=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=750 -CONFIG_USERMAIN_STACKSIZE=2500 -CONFIG_PTHREAD_STACK_MIN=512 -CONFIG_PTHREAD_STACK_DEFAULT=2048 -# CONFIG_LIB_SYSCALL is not set - -# -# Device Drivers -# -# CONFIG_DISABLE_POLL is not set -CONFIG_DEV_NULL=y -# CONFIG_DEV_ZERO is not set -# CONFIG_DEV_URANDOM is not set -# CONFIG_DEV_LOOP is not set - -# -# Buffering -# -# CONFIG_DRVR_WRITEBUFFER is not set -# CONFIG_DRVR_READAHEAD is not set -# CONFIG_RAMDISK is not set -# CONFIG_CAN is not set -# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set -# CONFIG_ARCH_HAVE_PWM_MULTICHAN is not set -# CONFIG_PWM is not set -CONFIG_ARCH_HAVE_I2CRESET=y -CONFIG_I2C=y -# CONFIG_I2C_SLAVE is not set -# CONFIG_I2C_POLLED is not set -CONFIG_I2C_RESET=y -# CONFIG_I2C_TRACE is not set -# CONFIG_I2C_DRIVER is not set -# CONFIG_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 -# 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=y -# 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=y -CONFIG_USART3_SERIALDRIVER=y -# CONFIG_USART4_SERIALDRIVER is not set -# CONFIG_USART5_SERIALDRIVER is not set -CONFIG_USART6_SERIALDRIVER=y -# CONFIG_USART7_SERIALDRIVER is not set -# CONFIG_USART8_SERIALDRIVER is not set -# CONFIG_OTHER_UART_SERIALDRIVER is not set -CONFIG_MCU_SERIAL=y -CONFIG_STANDARD_SERIAL=y -CONFIG_SERIAL_NPOLLWAITERS=2 -# CONFIG_SERIAL_IFLOWCONTROL is not set -# CONFIG_SERIAL_OFLOWCONTROL is not set -CONFIG_SERIAL_DMA=y -CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y -# CONFIG_USART1_SERIAL_CONSOLE is not set -# CONFIG_USART2_SERIAL_CONSOLE is not set -CONFIG_USART3_SERIAL_CONSOLE=y -# CONFIG_UART4_SERIAL_CONSOLE is not set -# CONFIG_UART5_SERIAL_CONSOLE is not set -# CONFIG_USART6_SERIAL_CONSOLE is not set -# CONFIG_OTHER_SERIAL_CONSOLE is not set -# CONFIG_NO_SERIAL_CONSOLE is not set - -# -# USART1 Configuration -# -CONFIG_USART1_RXBUFSIZE=128 -CONFIG_USART1_TXBUFSIZE=32 -CONFIG_USART1_BAUD=57600 -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=y - -# -# USART2 Configuration -# -CONFIG_USART2_RXBUFSIZE=300 -CONFIG_USART2_TXBUFSIZE=300 -CONFIG_USART2_BAUD=57600 -CONFIG_USART2_BITS=8 -CONFIG_USART2_PARITY=0 -CONFIG_USART2_2STOP=0 -# CONFIG_USART2_IFLOWCONTROL is not set -# CONFIG_USART2_OFLOWCONTROL is not set -CONFIG_USART2_DMA=y - -# -# USART3 Configuration -# -CONFIG_USART3_RXBUFSIZE=32 -CONFIG_USART3_TXBUFSIZE=256 -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=y - -# -# UART4 Configuration -# -CONFIG_UART4_RXBUFSIZE=256 -CONFIG_UART4_TXBUFSIZE=256 -CONFIG_UART4_BAUD=115200 -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=y - -# -# UART5 Configuration -# -CONFIG_UART5_RXBUFSIZE=300 -CONFIG_UART5_TXBUFSIZE=300 -CONFIG_UART5_BAUD=57600 -CONFIG_UART5_BITS=8 -CONFIG_UART5_PARITY=0 -CONFIG_UART5_2STOP=0 -# CONFIG_UART5_IFLOWCONTROL is not set -# CONFIG_UART5_OFLOWCONTROL is not set -CONFIG_UART5_DMA=y - -# -# USART6 Configuration -# -CONFIG_USART6_RXBUFSIZE=128 -CONFIG_USART6_TXBUFSIZE=64 -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=y -# CONFIG_PSEUDOTERM is not set -CONFIG_USBDEV=y - -# -# USB Device Controller Driver Options -# -# CONFIG_USBDEV_ISOCHRONOUS is not set -# CONFIG_USBDEV_DUALSPEED is not set -# CONFIG_USBDEV_SELFPOWERED is not set -CONFIG_USBDEV_BUSPOWERED=y -CONFIG_USBDEV_MAXPOWER=500 -# CONFIG_USBDEV_DMA is not set -# CONFIG_ARCH_USBDEV_STALLQUEUE is not set -# CONFIG_USBDEV_TRACE is not set - -# -# USB Device Class Driver Options -# -# CONFIG_USBDEV_COMPOSITE is not set -# CONFIG_PL2303 is not set -CONFIG_CDCACM=y -# CONFIG_CDCACM_CONSOLE is not set -CONFIG_CDCACM_EP0MAXPACKET=64 -CONFIG_CDCACM_EPINTIN=1 -CONFIG_CDCACM_EPINTIN_FSSIZE=64 -CONFIG_CDCACM_EPINTIN_HSSIZE=64 -CONFIG_CDCACM_EPBULKOUT=3 -CONFIG_CDCACM_EPBULKOUT_FSSIZE=64 -CONFIG_CDCACM_EPBULKOUT_HSSIZE=512 -CONFIG_CDCACM_EPBULKIN=2 -CONFIG_CDCACM_EPBULKIN_FSSIZE=64 -CONFIG_CDCACM_EPBULKIN_HSSIZE=512 -CONFIG_CDCACM_NRDREQS=4 -CONFIG_CDCACM_NWRREQS=4 -CONFIG_CDCACM_BULKIN_REQLEN=96 -CONFIG_CDCACM_RXBUFSIZE=270 -CONFIG_CDCACM_TXBUFSIZE=300 -CONFIG_CDCACM_VENDORID=0x26ac -CONFIG_CDCACM_PRODUCTID=0x0010 -CONFIG_CDCACM_VENDORSTR="The Autopilot" -CONFIG_CDCACM_PRODUCTSTR="PX4 TAP v1.x" -# CONFIG_USBMSC 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_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_CCTYPE is not set -# CONFIG_EXAMPLES_CHAT is not set -# CONFIG_EXAMPLES_CONFIGDATA is not set -# CONFIG_EXAMPLES_CPUHOG is not set -# CONFIG_EXAMPLES_CXXTEST is not set -# CONFIG_EXAMPLES_DHCPD is not set -# CONFIG_EXAMPLES_ELF is not set -# CONFIG_EXAMPLES_FSTEST is not set -# CONFIG_EXAMPLES_FTPC is not set -# CONFIG_EXAMPLES_FTPD is not set -# CONFIG_EXAMPLES_HELLO is not set -# CONFIG_EXAMPLES_HELLOXX is not set -# CONFIG_EXAMPLES_HIDKBD is not set -# CONFIG_EXAMPLES_IGMP is not set -# CONFIG_EXAMPLES_JSON is not set -# CONFIG_EXAMPLES_MEDIA is not set -# CONFIG_EXAMPLES_MM is not set -# CONFIG_EXAMPLES_MODBUS is not set -CONFIG_EXAMPLES_MOUNT=y -# CONFIG_EXAMPLES_MOUNT_BLOCKDEVICE is not set -CONFIG_EXAMPLES_MOUNT_NSECTORS=2048 -CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512 -CONFIG_EXAMPLES_MOUNT_RAMDEVNO=0 -CONFIG_EXAMPLES_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_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=y -# CONFIG_NSH_DISABLE_DATE is not set -CONFIG_NSH_DISABLE_DD=y -CONFIG_NSH_DISABLE_DF=y -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_CODECS_BUFSIZE=128 -CONFIG_NSH_PROC_MOUNTPOINT="/proc" -CONFIG_NSH_FILEIOSIZE=512 -CONFIG_NSH_STRERROR=y - -# -# Scripting Support -# -# CONFIG_NSH_DISABLESCRIPT is not set -# CONFIG_NSH_DISABLE_ITEF is not set -# CONFIG_NSH_DISABLE_LOOPS is not set -CONFIG_NSH_ROMFSETC=y -# CONFIG_NSH_ROMFSRC is not set -CONFIG_NSH_ROMFSMOUNTPT="/etc" -CONFIG_NSH_INITSCRIPT="init.d/rcS" -CONFIG_NSH_ROMFSDEVNO=0 -CONFIG_NSH_ROMFSSECTSIZE=128 -# CONFIG_NSH_DEFAULTROMFS is not set -CONFIG_NSH_ARCHROMFS=y -# CONFIG_NSH_CUSTOMROMFS is not set -CONFIG_NSH_FATDEVNO=1 -CONFIG_NSH_FATSECTSIZE=512 -CONFIG_NSH_FATNSECTORS=1024 -CONFIG_NSH_FATMOUNTPT="/tmp" - -# -# Console Configuration -# -CONFIG_NSH_CONSOLE=y -# CONFIG_NSH_USBCONSOLE is not set -# CONFIG_NSH_ALTCONDEV is not set -CONFIG_NSH_ARCHINIT=y -# CONFIG_NSH_LOGIN is not set -# CONFIG_NSH_CONSOLE_LOGIN is not set - -# -# NxWidgets/NxWM -# - -# -# Platform-specific Support -# -# CONFIG_PLATFORM_CONFIGDATA is not set -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_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/tap-v1/scripts/ld.script b/platforms/nuttx/nuttx-configs/tap-v1/scripts/ld.script deleted file mode 100644 index 710a5d1309..0000000000 --- a/platforms/nuttx/nuttx-configs/tap-v1/scripts/ld.script +++ /dev/null @@ -1,151 +0,0 @@ -/**************************************************************************** - * configs/tap-v1/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 16 KiB of flash is reserved for the bootloader. - * Paramater storage will use the next 2 16KiB Sectors. - */ - -MEMORY -{ - flash (rx) : ORIGIN = 0x0800C000, LENGTH = 976K - 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/boards/tap-v1/CMakeLists.txt b/src/drivers/boards/tap-v1/CMakeLists.txt deleted file mode 100644 index 8e853e5373..0000000000 --- a/src/drivers/boards/tap-v1/CMakeLists.txt +++ /dev/null @@ -1,52 +0,0 @@ -############################################################################ -# -# Copyright (c) 2016 PX4 Development Team. All rights reserved. -# Author: David Sidrane -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 3. Neither the name 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 - pwr.c - sdio.c - spi.c - timer_config.c - usb.c -) - -target_link_libraries(drivers_board - PRIVATE - nuttx_apps # up_cxxinitialize - nuttx_arch # sdio - nuttx_drivers # sdio - drivers__led # drv_led_start - parameters # param_init - ) diff --git a/src/drivers/boards/tap-v1/board_config.h b/src/drivers/boards/tap-v1/board_config.h deleted file mode 100644 index 9bd3445c14..0000000000 --- a/src/drivers/boards/tap-v1/board_config.h +++ /dev/null @@ -1,351 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 PX4 Development Team. All rights reserved. - * Author: David Sidrane - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name 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 - * - * TAP_V1 internal definitions - */ - -#pragma once - -/**************************************************************************************************** - * Included Files - ****************************************************************************************************/ - -#include -#include -#include - -/**************************************************************************************************** - * Definitions - ****************************************************************************************************/ -/* Configuration ************************************************************************************/ - -/* PX4FMU GPIOs ***********************************************************************************/ -/* LEDs - * - * PC4 BLUE_LED D4 Blue LED cathode - * PC5 RED_LED D5 Red LED cathode -*/ - -#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN4) -#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN5) -#define GPIO_BLUE_LED GPIO_LED1 -#define GPIO_RED_LED GPIO_LED2 -/* - * SPI - * - * Peripheral Port Signal Name CONN - * SPI2_NSS PB12 SD_SPI2_NSS SD-2 CS - * SPI2_SCK PB13 SD_SPI2_SCK SD-5 CLK - * SPI2_MISO PB14 SD_SPI2_MISO SD-7 D0 - * SPI2_MOSI PB15 SD_SPI2_MOSI SD-3 DI - * - * PC2 SD_SW SD-9 SW - * - */ -#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN12) -#define GPIO_SPI_SD_SW (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN2) - - -/* - * I2C busses - * - * Peripheral Port Signal Name CONN - * I2C1_SDA PB9 I2C1_SDA J2-4,9,16,21 mpu6050, U4 MS6507 - * I2C1_SDL PB8 I2C1_SCL J2-3,10,15,22 mpu6050, U4 MS6507 - * - * I2C2_SDA PB11 Sonar Echo/I2C_SDA JP2-31,32 - * I2C2_SDL PB10 Sonar Trig/I2C_SCL JP2-29,30 - * - * I2C3_SDA PC9 COMPASS_I2C3_SDA JP1-27,28 - * I2C3_SDL PA8 COMPASS_I2C3_SCL JP1-25,26 - * - */ -#define PX4_I2C_BUS_ONBOARD 1 -#define PX4_I2C_BUS_SONAR 2 -#define PX4_I2C_BUS_EXPANSION 3 - -#define PX4_I2C_BUS_ONBOARD_HZ 400000 -#define PX4_I2C_BUS_SONAR_HZ 400000 -#define PX4_I2C_BUS_EXPANSION_HZ 400000 - -#define BOARD_NUMBER_I2C_BUSES 3 -#define BOARD_I2C_BUS_CLOCK_INIT {PX4_I2C_BUS_ONBOARD_HZ, PX4_I2C_BUS_SONAR_HZ, PX4_I2C_BUS_EXPANSION_HZ} - - -/* - * Devices on the onboard bus. - * - * Note that these are unshifted addresses (not includinf R/W). - */ - -/* - * The slave address of the MPU-60X0 is b110100X which is 7 bits long. - * The LSB bit of the 7 bit address is determined by the logic level - * on pin AD0. This allows two MPU-60X0s to be connected to the same I2C bus. - * When used in this configuration, the address of the one of the devices - * should be b1101000 (pin AD0 is logic low) and the address of the other - * should be b1101001 (pin AD0 is logic high). - */ -#define PX4_I2C_MPU6050_ADDR 0x68 - -/* - * 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 - * PC0 VOLTAGE JP2-13,14 - 1.84 @16.66 1.67 @15.12 Scale 0.1105 - * - */ -#define ADC_CHANNELS (1 << 10) -/* todo:Revisit - cannnot tell from schematic - some could be ADC */ - -// ADC defines to be used in sensors.cpp to read from a particular channel -#define ADC_BATTERY_VOLTAGE_CHANNEL 10 -#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1)) - -/* Define Battery 1 Voltage Divider - * Use Default for A per V - */ - -#define BOARD_BATTERY1_V_DIV (9.0f) - -/* No User GPIOs - * - * TIM3_CH1 PA6 LED_R JP2-23,24 - * TIM3_CH2 PA7 LED_G JP2-25,26 - * TIM3_CH3 PB0 LED_B JP2-27,28 - * TIM3_CH4 PB1 nPWM_1 AUX1(Landing Gear) JP1-21,22 - * - * I2C2_SDA PB11 Sonar Echo/I2C_SDA JP2-31,32 - * I2C2_SDL PB10 Sonar Trig/I2C_SCL JP2-29,30 - */ - -/* - * Tone alarm output - */ -/* todo:Revisit - cannnot tell from schematic - one could be tone alarm*/ -#define TONE_ALARM_TIMER 8 /* timer 8 */ -#define TONE_ALARM_CHANNEL 3 /* channel 3 */ -#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8) -#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) - -/* - * PWM - * - * Four PWM outputs can be configured on pins - * - * - * Peripheral Port Signal Name CONN - * TIM3_CH1 PA6 LED_R JP2-23,24 - * TIM3_CH2 PA7 LED_G JP2-25,26 - * TIM3_CH3 PB0 LED_B JP2-27,28 - * TIM3_CH4 PB1 nPWM_1 AUX1(Landing Gear) JP1-21,22 - * - */ -#define GPIO_TIM3_CH1OUT GPIO_TIM3_CH1OUT_1 -#define GPIO_TIM3_CH2OUT GPIO_TIM3_CH2OUT_1 -#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_1 -#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_1 -#define DIRECT_PWM_OUTPUT_CHANNELS 4 - -#define GPIO_TIM3_CH1IN GPIO_TIM3_CH1IN_1 -#define GPIO_TIM3_CH2IN GPIO_TIM3_CH2IN_1 -#define GPIO_TIM3_CH3IN GPIO_TIM3_CH3IN_1 -#define GPIO_TIM3_CH4IN GPIO_TIM3_CH4IN_1 -#define DIRECT_INPUT_TIMER_CHANNELS 4 - -#define BOARD_HAS_LED_PWM -#define BOARD_HAS_SHARED_PWM_TIMERS -#define LED_TIM3_CH1OUT GPIO_TIM3_CH1OUT -#define LED_TIM3_CH2OUT GPIO_TIM3_CH2OUT -#define LED_TIM3_CH3OUT GPIO_TIM3_CH3OUT - -#define BOARD_PWM_DRIVE_ACTIVE_LOW 1 - - -/* USB OTG FS - * - * PA9 OTG_FS_VBUS VBUS sensing - */ -#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN9) - -#define RC_SERIAL_PORT "/dev/ttyS5" /* No HW invert support */ - -/* High-resolution timer - */ -#define HRT_TIMER 1 /* use timer1 for the HRT */ -#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ - -#define BOARD_NAME "TAP_V1" - -/* By Providing BOARD_ADC_USB_CONNECTED this board support the ADC - * system_power interface, and herefore provides the true logic - * GPIO BOARD_ADC_xxxx macros. - */ -#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) -#define BOARD_ADC_BRICK_VALID (1) -#define BOARD_ADC_SERVO_VALID (1) -#define BOARD_ADC_PERIPH_5V_OC (0) -#define BOARD_ADC_HIPOWER_5V_OC (0) - -#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS - -#define BOARD_HAS_POWER_CONTROL 1 - -/* This board provides a DMA pool and APIs */ - -#define BOARD_DMA_ALLOC_POOL_SIZE 5120 - -#define MS_PWR_BUTTON_DOWN 200 -#define KEY_AD_GPIO (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTC|GPIO_PIN1) -#define POWER_ON_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) -#define POWER_OFF_GPIO (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN4) - -#define GPIO_S0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN15) -#define GPIO_S1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN14) -#define GPIO_S2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) - -#define GPIO_PCON_RADIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN3) -#define RF_RADIO_POWER_CONTROL(_on_true) px4_arch_gpiowrite(GPIO_PCON_RADIO, !(_on_true)) - -#define GPIO_TEMP_CONT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN4) -#define TEMP_CONTROL(_on_true) px4_arch_gpiowrite(GPIO_TEMP_CONT, (_on_true)) - -#define FLASH_BASED_PARAMS - -__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. - * - ****************************************************************************************************/ - -extern void stm32_spiinitialize(void); - -/************************************************************************************ - * Name: stm32_spi_bus_initialize - * - * Description: - * Called to configure SPI Buses. - * - ************************************************************************************/ - -extern int stm32_spi_bus_initialize(void); - -/**************************************************************************************************** - * Name: board_spi_reset board_peripheral_reset - * - * Description: - * Called to reset SPI and the perferal bus - * - ****************************************************************************************************/ - -#define board_spi_reset(ms) -#define board_peripheral_reset(ms) - -/**************************************************************************************************** - * Name: stm32_usbinitialize - * - * Description: - * Called to configure USB IO. - * - ****************************************************************************************************/ - -extern void stm32_usbinitialize(void); - -/************************************************************************************ - * Name: board_sdio_initialize - * - * Description: - * Called to configure SDIO. - * - ************************************************************************************/ - -extern int board_sdio_initialize(void); - -/**************************************************************************** - * Name: board_i2c_initialize - * - * Description: - * Called to set I2C bus frequencies. - * - ****************************************************************************/ - -int board_i2c_initialize(void); - -/************************************************************************************ - * Name: board_pwr_init() - * - * Description: - * Called to configure power control for the tap-v1 board. - * - * Input Parameters: - * stage- 0 for boot, 1 for board init - * - ************************************************************************************/ - -void board_pwr_init(int stage); - -/**************************************************************************** - * Name: board_pwr_button_down - * - * Description: - * Called to Read the logical state of the power button - ****************************************************************************/ - -bool board_pwr_button_down(void); - -#include "../common/board_common.h" - -#endif /* __ASSEMBLY__ */ - -__END_DECLS diff --git a/src/drivers/boards/tap-v1/init.c b/src/drivers/boards/tap-v1/init.c deleted file mode 100644 index a19bfc47cf..0000000000 --- a/src/drivers/boards/tap-v1/init.c +++ /dev/null @@ -1,400 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 PX4 Development Team. All rights reserved. - * Author: David Sidrane - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name 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 tap-v1_init.c - * - * tap-v1-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 "board_config.h" -#include "stm32_uart.h" - -#include - -#include -#include - -#include -#include -#include -#include -#include - -# if defined(FLASH_BASED_PARAMS) -# include -#endif - -/**************************************************************************** - * 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: 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. - * - ************************************************************************************/ - -__EXPORT void stm32_boardinitialize(void) -{ - /* Hold power state */ - - board_pwr_init(0); - - /* TEMP ctrl Off (active high, init is clear) */ - - stm32_configgpio(GPIO_TEMP_CONT); - - - /* Select 0 */ - - stm32_configgpio(GPIO_S0); - stm32_configgpio(GPIO_S1); - stm32_configgpio(GPIO_S2); - - /* Radio Off (active low, init is set) */ - - stm32_configgpio(GPIO_PCON_RADIO); - - - /* configure always-on ADC pins */ - - stm32_configgpio(GPIO_ADC1_IN10); - - - /* configure USB interfaces */ - - stm32_usbinitialize(); - - /* configure SPI interfaces */ - - stm32_spiinitialize(); - - /* configure LEDs */ - - board_autoled_initialize(); -} - -/**************************************************************************** - * Name: board_app_initialize - * - * Description: - * Perform architecture specific initialization - * - ****************************************************************************/ - -__EXPORT int board_app_initialize(uintptr_t arg) -{ - int result; - -#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); - - board_pwr_init(1); - -#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_AMBER); - led_off(LED_BLUE); - -#if defined(FLASH_BASED_PARAMS) - static sector_descriptor_t sector_map[] = { - {1, 16 * 1024, 0x08004000}, - {2, 16 * 1024, 0x08008000}, - {0, 0, 0}, - }; - - /* Initalizee the flashfs layer to use heap allocated memory */ - - result = parameter_flashfs_init(sector_map, NULL, 0); - - if (result != OK) { - message("[boot] FAILED to init params in FLASH %d\n", result); - led_on(LED_AMBER); - return -ENODEV; - } - -#endif - - /* Init the microSD slot */ - - result = board_sdio_initialize(); - - if (result != OK) { - led_on(LED_AMBER); - return -ENODEV; - } - - return OK; -} diff --git a/src/drivers/boards/tap-v1/led.c b/src/drivers/boards/tap-v1/led.c deleted file mode 100644 index b09d04216c..0000000000 --- a/src/drivers/boards/tap-v1/led.c +++ /dev/null @@ -1,107 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 PX4 Development Team. All rights reserved. - * Author: David Sidrane - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name 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 tap-v1_led.c - * - * TAP_V1 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 - -__EXPORT void led_init(void) -{ - /* Configure LED1-2 GPIOs for output */ - - stm32_configgpio(GPIO_BLUE_LED); - stm32_configgpio(GPIO_RED_LED); -} - -__EXPORT void led_on(int led) -{ - if (led == 0) { - /* Pull down to switch on */ - stm32_gpiowrite(GPIO_BLUE_LED, false); - } - - if (led == 1) { - /* Pull down to switch on */ - stm32_gpiowrite(GPIO_RED_LED, false); - } -} - -__EXPORT void led_off(int led) -{ - if (led == 0) { - /* Pull up to switch off */ - stm32_gpiowrite(GPIO_BLUE_LED, true); - } - - if (led == 1) { - /* Pull up to switch off */ - stm32_gpiowrite(GPIO_RED_LED, true); - } -} - -__EXPORT void led_toggle(int led) -{ - if (led == 0) { - stm32_gpiowrite(GPIO_BLUE_LED, !stm32_gpioread(GPIO_BLUE_LED)); - } - - if (led == 1) { - stm32_gpiowrite(GPIO_RED_LED, !stm32_gpioread(GPIO_RED_LED)); - } -} diff --git a/src/drivers/boards/tap-v1/pwr.c b/src/drivers/boards/tap-v1/pwr.c deleted file mode 100644 index 610bce76d1..0000000000 --- a/src/drivers/boards/tap-v1/pwr.c +++ /dev/null @@ -1,185 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2016 PX4 Development Team. All rights reserved. - * Author: David Sidrane - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name 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 tap-v1_pwr.c - * - * Board-specific SPI functions. - */ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include -#include -#include - -#include -#include - -#include "up_arch.h" -#include "board_config.h" -#include - -extern void led_on(int led); -extern void led_off(int led); - -static struct timespec time_down; - - -/************************************************************************************ - * Private Data - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -static int default_power_button_state_notification(board_power_button_state_notification_e request) -{ -// syslog(0,"%d\n", request); - return PWR_BUTTON_RESPONSE_SHUT_DOWN_NOW; -} - - -static power_button_state_notification_t power_state_notification = default_power_button_state_notification; - -int board_register_power_state_notification_cb(power_button_state_notification_t cb) -{ - power_state_notification = cb; - - if (board_pwr_button_down() && (time_down.tv_nsec != 0 || time_down.tv_sec != 0)) { - // make sure we don't miss the first event - power_state_notification(PWR_BUTTON_DOWN); - } - - return OK; -} - -int board_shutdown() -{ - stm32_pwr_enablebkp(true); - /* XXX wow, this is evil - write a magic number into backup register zero */ - *(uint32_t *)0x40002850 = 0xdeaddead; - stm32_pwr_enablebkp(false); - up_mdelay(50); - up_systemreset(); - - while (1); - - return 0; -} - -static int board_button_irq(int irq, FAR void *context, FAR void *args) -{ - if (board_pwr_button_down()) { - - led_on(BOARD_LED_RED); - clock_gettime(CLOCK_REALTIME, &time_down); - power_state_notification(PWR_BUTTON_DOWN); - - } else { - - power_state_notification(PWR_BUTTON_UP); - - led_off(BOARD_LED_RED); - - struct timespec now; - - clock_gettime(CLOCK_REALTIME, &now); - - uint64_t tdown_ms = time_down.tv_sec * 1000 + time_down.tv_nsec / 1000000; - - uint64_t tnow_ms = now.tv_sec * 1000 + now.tv_nsec / 1000000; - - if (tdown_ms != 0 && (tnow_ms - tdown_ms) >= MS_PWR_BUTTON_DOWN) { - - led_on(BOARD_LED_BLUE); - - if (power_state_notification(PWR_BUTTON_REQUEST_SHUT_DOWN) == PWR_BUTTON_RESPONSE_SHUT_DOWN_NOW) { - up_mdelay(200); - board_shutdown(); - } - - } else { - power_state_notification(PWR_BUTTON_IDEL); - } - } - - return OK; -} - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: board_pwr_init() - * - * Description: - * Called to configure power control for the tap-v1 board. - * - * Input Parameters: - * stage- 0 for boot, 1 for board init - * - ************************************************************************************/ - -void board_pwr_init(int stage) -{ - if (stage == 0) { - stm32_configgpio(POWER_ON_GPIO); - stm32_configgpio(KEY_AD_GPIO); - } - - if (stage == 1) { - stm32_gpiosetevent(KEY_AD_GPIO, true, true, true, board_button_irq, NULL); - } -} - -/**************************************************************************** - * Name: board_pwr_button_down - * - * Description: - * Called to Read the logical state of the active low power button. - * - ****************************************************************************/ - -bool board_pwr_button_down(void) -{ - return 0 == stm32_gpioread(KEY_AD_GPIO); -} diff --git a/src/drivers/boards/tap-v1/sdio.c b/src/drivers/boards/tap-v1/sdio.c deleted file mode 100644 index b29432e3d2..0000000000 --- a/src/drivers/boards/tap-v1/sdio.c +++ /dev/null @@ -1,122 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2016 PX4 Development Team. All rights reserved. - * Author: David Sidrane - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name 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 tap-v1_sdio.c - * - * Board-specific SDIOfunctions. - */ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include -#include -#include - -#include "up_arch.h" -#include "chip.h" -#include "stm32.h" -#include "board_config.h" - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -/* Configuration ************************************************************/ - -/* Debug ********************************************************************/ - -#ifdef CONFIG_CPP_HAVE_VARARGS -# ifdef CONFIG_DEBUG -# define message(...) lowsyslog(__VA_ARGS__) -# else -# define message(...) printf(__VA_ARGS__) -# endif -#else -# ifdef CONFIG_DEBUG -# define message lowsyslog -# else -# define message printf -# endif -#endif - -/************************************************************************************ - * Private Data - ************************************************************************************/ -static struct spi_dev_s *spi; - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: board_sdio_initialize - * - * Description: - * Called to configure SDIO. - * - ************************************************************************************/ - -__EXPORT int board_sdio_initialize(void) -{ - /* Get the SPI port for the microSD slot */ - - spi = stm32_spibus_initialize(CONFIG_NSH_MMCSDSPIPORTNO); - - if (!spi) { - 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, spi); - - if (result != OK) { - message("[boot] FAILED to bind SPI port 2 to the MMCSD driver\n"); - return -ENODEV; - } - - return OK; -} - diff --git a/src/drivers/boards/tap-v1/spi.c b/src/drivers/boards/tap-v1/spi.c deleted file mode 100644 index 37571725d2..0000000000 --- a/src/drivers/boards/tap-v1/spi.c +++ /dev/null @@ -1,85 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 PX4 Development Team. All rights reserved. - * Author: David Sidrane - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name 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 tap-v1_spi.c - * - * Board-specific SPI functions. - */ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include -#include - -#include -#include - -#include "board_config.h" - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: stm32_spiinitialize - * - * Description: - * Called to configure SPI chip select GPIO pins for the tap-v1 board. - * - ************************************************************************************/ - -__EXPORT void stm32_spiinitialize(void) -{ - stm32_configgpio(GPIO_SPI_CS_SDCARD); - stm32_configgpio(GPIO_SPI_SD_SW); -} - - -__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) -{ - /* there can only be one device on this bus, so always select it */ - stm32_gpiowrite(GPIO_SPI_CS_SDCARD, !selected); -} - -__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) -{ - return !stm32_gpioread(GPIO_SPI_SD_SW); -} - diff --git a/src/drivers/boards/tap-v1/timer_config.c b/src/drivers/boards/tap-v1/timer_config.c deleted file mode 100644 index 2b0d659422..0000000000 --- a/src/drivers/boards/tap-v1/timer_config.c +++ /dev/null @@ -1,109 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 PX4 Development Team. All rights reserved. - * Author: David Sidrane - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name 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 tap-v1_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_TIM3_BASE, - .clock_register = STM32_RCC_APB1ENR, - .clock_bit = RCC_APB1ENR_TIM3EN, - .clock_freq = STM32_APB1_TIM3_CLKIN, - .first_channel_index = 0, - .last_channel_index = 0, - .handler = io_timer_handler0, - .vectorno = STM32_IRQ_TIM3, - } -}; - -__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { - { - .gpio_out = GPIO_TIM3_CH4OUT, - .gpio_in = GPIO_TIM3_CH4IN, - .timer_index = 0, - .timer_channel = 4, - .ccr_offset = STM32_GTIM_CCR4_OFFSET, - .masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF - } -}; - -__EXPORT const struct io_timers_t led_pwm_timers[MAX_LED_TIMERS] = { - { - .base = STM32_TIM3_BASE, - .clock_register = STM32_RCC_APB1ENR, - .clock_bit = RCC_APB1ENR_TIM3EN, - .clock_freq = STM32_APB1_TIM3_CLKIN, - .vectorno = STM32_IRQ_TIM3, - .first_channel_index = 0, - .last_channel_index = 2, - } -}; - -__EXPORT const struct timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = { - { - .gpio_out = LED_TIM3_CH1OUT, - .gpio_in = 0, - .timer_index = 0, - .timer_channel = 1, - }, - { - .gpio_out = LED_TIM3_CH2OUT, - .gpio_in = 0, - .timer_index = 0, - .timer_channel = 2, - }, - { - .gpio_out = LED_TIM3_CH3OUT, - .gpio_in = 0, - .timer_index = 0, - .timer_channel = 3, - } -}; diff --git a/src/drivers/boards/tap-v1/usb.c b/src/drivers/boards/tap-v1/usb.c deleted file mode 100644 index 3bed1680c5..0000000000 --- a/src/drivers/boards/tap-v1/usb.c +++ /dev/null @@ -1,127 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 PX4 Development Team. All rights reserved. - * Author: David Sidrane - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name 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 tap-v1_usb.c - * - * Board-specific USB functions. - */ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include -#include -#include - -#include -#include - -#include "up_arch.h" -#include "stm32.h" -#include "board_config.h" -#include "stm32_otgfs.h" - -#define GPIO_DP (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN12) - - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: stm32_usbinitialize - * - * Description: - * Called to setup USB-related GPIO pins for the tap-v1 board. - * - ************************************************************************************/ - -__EXPORT void stm32_usbinitialize(void) -{ - /* The OTG FS has an internal soft pull-up. - * The HW also has one too. So we need to overcome it. - * to force a soft disconnect. - */ - - /* Issue the Reset to the OTGFS Block */ - - uint32_t regval = getreg32(STM32_RCC_AHB2RSTR); - regval |= RCC_AHB2RSTR_OTGFSRST; - putreg32(regval, STM32_RCC_AHB2RSTR); - - /* Drive the DP Pin Low */ - - stm32_configgpio(GPIO_DP); - - /* Release the Reset to the OTGFS Block */ - - regval &= ~RCC_AHB2RSTR_OTGFSRST; - - putreg32(regval, STM32_RCC_AHB2RSTR); - - - /* Configure the OTG FS VBUS sensing GPIO */ - - px4_arch_configgpio(GPIO_OTGFS_VBUS); -} - -/************************************************************************************ - * 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) -{ - //ulldbg("resume: %d\n", resume); -} -